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



Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019