Main MRPT website > C++ reference
MRPT logo
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-2014, 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/utils/TCamera.h>
18 
20 
21 
22 namespace mrpt
23 {
24  namespace hwdrivers
25  {
26  using namespace std;
27  using namespace mrpt::slam;
28 
29  /** A class to interface a Rovio robot (manufactured by WowWee).
30  * Supports: Simple motion commands, video streaming.
31  * \ingroup mrpt_hwdrivers_grp
32  */
34  {
35  private:
41 
42  mrpt::slam::CObservationImagePtr buffer_img;
44 
45 
46  /** This function takes a frame and waits until getLastImage ask for it, and so on.
47  */
48  void thread_video();
49 
50  bool send_cmd_action(int act, int speed);
51 
52  bool path_management(int act);
53 
54  bool path_management(int act, const string &path_name);
55 
56  bool general_command(int act, string &response, string &errormsg);
57 
58 
59  public:
60  struct TOptions
61  {
62  string IP;
63  string user;
64  string password;
65 
66  mrpt::utils::TCamera cameraParams; // Mat. cam. preguntar paco
67 
68  TOptions();
69  } options;
70 
71  enum status {idle, driving_home, docking, executing_path, recording_path};
72 
73  struct TRovioState{
75  unsigned int nss; //Navigation Signal Strength
76  unsigned int wss; //Wifi Signal Strength
77  };
78 
79  struct TEncoders{
80  int left;
81  int right;
82  int rear;
84  {
85  left = 0;
86  right = 0;
87  rear = 0;
88  }
89  }encoders;
90 
91 
92  /** Establish conection with Rovio and log in its system: Important, fill out "options" members *BEFORE* calling this method.
93  * \exception std::runtime On errors
94  */
95  void initialize(); //string &errormsg_out, string url_out="150.214.109.134", string user_out="admin", string password_out="investigacion");
96 
97  /** move send Rovio the command to move in the specified direcction
98  * \param direction 'f'->forward, 'b'->backward, 'r'->right, 'l'->left
99  * \return False on error
100  */
101  bool move(char direction, int speed=5 );
102 
103  /** rotate send Rovio the command to rotate in the specified direcction
104  * 'r'->right, 'l'->left
105  * \return False on error
106  */
107  bool rotate(char direction, int speed=5 );
108 
109  /** Head positions
110  * \return False on error
111  */
112  bool takeHeadUp();
113  bool takeHeadMiddle();
114  bool takeHeadDown();
115 
116 
117  /* Path commands */
118  bool pathRecord();
119  bool pathRecordAbort();
120  bool pathRecordSave(const string &path_name);//Repasar const
121  bool pathDelete(const string &path_name);
122  /** Get list of saved paths
123  */
124  bool pathGetList(string &path_list);
125  bool pathRunForward();
126  bool pathRunBackward();
127  bool pathRunStop();
128  bool pathRunPause();
129  bool pathRename(const string &old_name, const string &new_name);
130 
131 
132  /** goHome(bool dock) drives Rovio in front of charging station if the paremeter dock is set to false, otherwise it also docks
133  * \return False on error
134  */
135  bool goHome(bool dock, int speed = 5);
136 
137  /** Loads the rovio camera calibration parameters (of leave the default ones if not found) (See CGenericSensor), then call to "loadConfig_sensorSpecific"
138  * \exception This method throws an exception with a descriptive message if some critical parameter is missing or has an invalid value.
139  */
140  void loadConfig(
141  const mrpt::utils::CConfigFileBase &configSource,
142  const std::string &section );
143 
144  /** This function launchs a thread with the function "thread_video()" which gets frames into a buffer.
145  * After calling this method, images can be obtained with getNextImageSync()
146  * \return False on error
147  * \sa getNextImageSync
148  */
149  bool retrieve_video();//como la protejo para que no se llame dos veces??????????????????????????????????????????????
150 
151  /** This function stops and joins the thread launched by "retrieve_video()".
152  * \return False on error
153  */
154  bool stop_video();
155 
156  /** Returns the next frame from Rovio's live video stream, after starting the live streaming with retrieve_video()
157  * \return False on error
158  * \sa retrieve_video, captureImageAsync
159  */
160  bool getNextImageSync(CObservationImagePtr& lastImage );
161 
162  /** Returns a snapshot from Rovio, if rectified is set true, the returned image is rectified with the parameters of intrinsic_matrix and distortion_matrix.
163  * This function works asynchronously and does not need to have enabled the live video streaming.
164  * \return False on error
165  * \sa captureImageSync
166  */
167  bool captureImageAsync( CImage&out_img, bool recttified);//string pict_name,
168 
169  bool isVideoStreamming() const; //!< Return true if video is streaming correctly \sa retrieve_video
170 
171 
172 //Rovio State
173  /** Returns a TRovioState with internal information of Rovio (State, Navigation Signal Strength, Wifi Signal Strength)
174  * \return False on error
175  */
176  bool getRovioState(TRovioState &state);
177 
178  /** Returns a TEncoders with information of Rovio encoders (since last read, it seems Rovio is continuously reading with unknown sample time)
179  * \return False on error
180  */
181  bool getEncoders(TEncoders &encoders);
182 
183  /** Returns the Rovio's pose
184  * \return False on error
185  */
186  bool getPosition(mrpt::math::TPose2D &out_pose);
187 
188 
189 
190  CRovio();
191  virtual ~CRovio();
192 
193  }; // End of class
194 
195  } // End of namespace
196 
197 } // End of namespace
198 
199 #endif
This class provides simple critical sections functionality.
A class for storing images as grayscale or RGB bitmaps.
Definition: CImage.h:97
bool m_videothread_initialized_error
Definition: CRovio.h:39
bool m_videothread_initialized_done
Definition: CRovio.h:38
mrpt::slam::CObservationImagePtr buffer_img
Definition: CRovio.h:42
STL namespace.
bool m_videothread_finished
Definition: CRovio.h:40
This namespace contains algorithms for SLAM, localization, map building, representation of robot's ac...
A class to interface a Rovio robot (manufactured by WowWee).
Definition: CRovio.h:33
This class allows loading and storing values and vectors of different types from a configuration text...
mrpt::utils::TCamera cameraParams
Definition: CRovio.h:66
mrpt::synch::CCriticalSection buffer_img_cs
Definition: CRovio.h:43
mrpt::system::TThreadHandle m_videoThread
Definition: CRovio.h:36
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool m_videothread_must_exit
Definition: CRovio.h:37
This structure contains the information needed to interface the threads API on each platform: ...
Definition: threads.h:25
Lightweight 2D pose.
#define HWDRIVERS_IMPEXP
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:31



Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014