MRPT  1.9.9
CRovio.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #ifndef CROVIO_H
11 #define CROVIO_H
12 
13 #include <mrpt/img/TCamera.h>
15 
17 
18 #include <thread>
19 
20 namespace mrpt::hwdrivers
21 {
22 /** A class to interface a Rovio robot (manufactured by WowWee).
23  * Supports: Simple motion commands, video streaming.
24  * \ingroup mrpt_hwdrivers_grp
25  */
26 class CRovio
27 {
28  private:
29  std::thread m_videoThread;
34 
36  std::mutex buffer_img_cs;
37 
38  /** This function takes a frame and waits until getLastImage ask for it, and
39  * so on.
40  */
41  void thread_video();
42 
43  bool send_cmd_action(int act, int speed);
44 
45  bool path_management(int act);
46 
47  bool path_management(int act, const std::string& path_name);
48 
49  bool general_command(int act, std::string& response, std::string& errormsg);
50 
51  public:
52  struct TOptions
53  {
57 
58  mrpt::img::TCamera cameraParams; // Mat. cam. preguntar paco
59 
60  TOptions();
61  } options;
62 
63  enum status
64  {
70  };
71 
72  struct TRovioState
73  {
75  unsigned int nss; // Navigation Signal Strength
76  unsigned int wss; // Wifi Signal Strength
77  };
78 
79  struct TEncoders
80  {
81  int left;
82  int right;
83  int rear;
85  {
86  left = 0;
87  right = 0;
88  rear = 0;
89  }
90  } encoders;
91 
92  /** Establish Connection with Rovio and log in its system: Important, fill
93  * out "options" members *BEFORE* calling this method.
94  * \exception std::runtime On errors
95  */
96  void initialize(); // string &errormsg_out, std::string
97  // url_out="150.214.109.134", std::string
98  // user_out="admin", std::string
99  // password_out="investigacion");
100 
101  /** move send Rovio the command to move in the specified direcction
102  * \param direction 'f'->forward, 'b'->backward, 'r'->right, 'l'->left
103  * \return False on error
104  */
105  bool move(char direction, int speed = 5);
106 
107  /** rotate send Rovio the command to rotate in the specified direcction
108  * 'r'->right, 'l'->left
109  * \return False on error
110  */
111  bool rotate(char direction, int speed = 5);
112 
113  /** Head positions
114  * \return False on error
115  */
116  bool takeHeadUp();
117  bool takeHeadMiddle();
118  bool takeHeadDown();
119 
120  /* Path commands */
121  bool pathRecord();
122  bool pathRecordAbort();
123  bool pathRecordSave(const std::string& path_name); // Repasar const
124  bool pathDelete(const std::string& path_name);
125  /** Get list of saved paths
126  */
127  bool pathGetList(std::string& path_list);
128  bool pathRunForward();
129  bool pathRunBackward();
130  bool pathRunStop();
131  bool pathRunPause();
132  bool pathRename(const std::string& old_name, const std::string& new_name);
133 
134  /** goHome(bool dock) drives Rovio in front of charging station if the
135  * paremeter dock is set to false, otherwise it also docks
136  * \return False on error
137  */
138  bool goHome(bool dock, int speed = 5);
139 
140  /** Loads the rovio camera calibration parameters (of leave the default ones
141  * if not found) (See CGenericSensor), then call to
142  * "loadConfig_sensorSpecific"
143  * \exception This method throws an exception with a descriptive message
144  * if some critical parameter is missing or has an invalid value.
145  */
146  void loadConfig(
147  const mrpt::config::CConfigFileBase& configSource,
148  const std::string& section);
149 
150  /** This function launchs a thread with the function "thread_video()" which
151  * gets frames into a buffer.
152  * After calling this method, images can be obtained with
153  * getNextImageSync()
154  * \return False on error
155  * \sa getNextImageSync
156  */
157  bool retrieve_video(); // como la protejo para que no se llame dos
158  // veces??????????????????????????????????????????????
159 
160  /** This function stops and joins the thread launched by "retrieve_video()".
161  * \return False on error
162  */
163  bool stop_video();
164 
165  /** Returns the next frame from Rovio's live video stream, after starting
166  * the live streaming with retrieve_video()
167  * \return False on error
168  * \sa retrieve_video, captureImageAsync
169  */
171 
172  /** Returns a snapshot from Rovio, if rectified is set true, the returned
173  * image is rectified with the parameters of intrinsic_matrix and
174  * distortion_matrix.
175  * This function works asynchronously and does not need to have enabled the
176  * live video streaming.
177  * \return False on error
178  * \sa captureImageSync
179  */
180  bool captureImageAsync(
181  mrpt::img::CImage& out_img, bool recttified); // string pict_name,
182 
183  /** Return true if video is streaming correctly \sa retrieve_video */
184  bool isVideoStreamming() const;
185 
186  // Rovio State
187  /** Returns a TRovioState with internal information of Rovio (State,
188  * Navigation Signal Strength, Wifi Signal Strength)
189  * \return False on error
190  */
191  bool getRovioState(TRovioState& state);
192 
193  /** Returns a TEncoders with information of Rovio encoders (since last read,
194  * it seems Rovio is continuously reading with unknown sample time)
195  * \return False on error
196  */
197  bool getEncoders(TEncoders& encoders);
198 
199  /** Returns the Rovio's pose
200  * \return False on error
201  */
202  bool getPosition(mrpt::math::TPose2D& out_pose);
203 
204  CRovio();
205  virtual ~CRovio();
206 
207 }; // End of class
208 
209 }
210 #endif
211 
212 
std::thread m_videoThread
Definition: CRovio.h:29
bool getNextImageSync(mrpt::obs::CObservationImage::Ptr &lastImage)
Returns the next frame from Rovio&#39;s live video stream, after starting the live streaming with retriev...
Definition: CRovio.cpp:325
bool getEncoders(TEncoders &encoders)
Returns a TEncoders with information of Rovio encoders (since last read, it seems Rovio is continuous...
Definition: CRovio.cpp:408
bool send_cmd_action(int act, int speed)
Definition: CRovio.cpp:68
bool path_management(int act)
Definition: CRovio.cpp:81
bool rotate(char direction, int speed=5)
rotate send Rovio the command to rotate in the specified direcction &#39;r&#39;->right, &#39;l&#39;->left ...
Definition: CRovio.cpp:135
bool pathDelete(const std::string &path_name)
Definition: CRovio.cpp:163
bool m_videothread_initialized_error
Definition: CRovio.h:32
bool m_videothread_initialized_done
Definition: CRovio.h:31
Contains classes for various device interfaces.
mrpt::img::TCamera cameraParams
Definition: CRovio.h:58
bool getPosition(mrpt::math::TPose2D &out_pose)
Returns the Rovio&#39;s pose.
Definition: CRovio.cpp:476
bool pathGetList(std::string &path_list)
Get list of saved paths.
Definition: CRovio.cpp:167
bool m_videothread_finished
Definition: CRovio.h:33
A class to interface a Rovio robot (manufactured by WowWee).
Definition: CRovio.h:26
This class allows loading and storing values and vectors of different types from a configuration text...
bool move(char direction, int speed=5)
move send Rovio the command to move in the specified direcction
Definition: CRovio.cpp:117
bool captureImageAsync(mrpt::img::CImage &out_img, bool recttified)
Returns a snapshot from Rovio, if rectified is set true, the returned image is rectified with the par...
Definition: CRovio.cpp:344
void initialize()
Establish Connection with Rovio and log in its system: Important, fill out "options" members BEFORE c...
Definition: CRovio.cpp:50
void thread_video()
This function takes a frame and waits until getLastImage ask for it, and so on.
Definition: CRovio.cpp:212
bool isVideoStreamming() const
Return true if video is streaming correctly.
Definition: CRovio.cpp:307
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:27
bool retrieve_video()
This function launchs a thread with the function "thread_video()" which gets frames into a buffer...
Definition: CRovio.cpp:278
GLsizei const GLchar ** string
Definition: glext.h:4101
struct mrpt::hwdrivers::CRovio::TEncoders encoders
bool stop_video()
This function stops and joins the thread launched by "retrieve_video()".
Definition: CRovio.cpp:312
bool getRovioState(TRovioState &state)
Returns a TRovioState with internal information of Rovio (State, Navigation Signal Strength...
Definition: CRovio.cpp:373
bool m_videothread_must_exit
Definition: CRovio.h:30
bool takeHeadUp()
Head positions.
Definition: CRovio.cpp:151
Lightweight 2D pose.
bool pathRecordSave(const std::string &path_name)
Definition: CRovio.cpp:159
bool goHome(bool dock, int speed=5)
goHome(bool dock) drives Rovio in front of charging station if the paremeter dock is set to false...
Definition: CRovio.cpp:190
struct mrpt::hwdrivers::CRovio::TOptions options
std::mutex buffer_img_cs
Definition: CRovio.h:36
bool general_command(int act, std::string &response, std::string &errormsg)
Definition: CRovio.cpp:105
void loadConfig(const mrpt::config::CConfigFileBase &configSource, const std::string &section)
Loads the rovio camera calibration parameters (of leave the default ones if not found) (See CGenericS...
Definition: CRovio.cpp:201
bool pathRename(const std::string &old_name, const std::string &new_name)
Definition: CRovio.cpp:177
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:130
mrpt::obs::CObservationImage::Ptr buffer_img
Definition: CRovio.h:35



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020