xbot.hpp
Go to the documentation of this file.
1 
9 /*****************************************************************************
10  ** Ifdefs
11  *****************************************************************************/
12 
13 #ifndef XBOT_HPP_
14 #define XBOT_HPP_
15 
16 /*****************************************************************************
17  ** Includes
18  *****************************************************************************/
19 
20 #include <ecl/config.hpp>
21 #include <ecl/devices.hpp>
22 #include <ecl/exceptions/standard_exception.hpp>
23 #include <ecl/threads.hpp>
24 #include <ecl/threads/mutex.hpp>
25 #include <iomanip>
26 #include <string>
27 #include "command.hpp"
28 #include "macros.hpp"
29 #include "modules.hpp"
31 #include "packets.hpp"
32 #include "parameters.hpp"
33 
34 /*****************************************************************************
35 ** Extern Templates
36 *****************************************************************************/
37 
38 #ifdef ECL_IS_WIN32
39 /* Help windows create common instances of sigslots across xbot dll
40  * and end user program (otherwise it creates two separate variables!) */
42 EXP_TEMPLATE template class xbot_PUBLIC
44 EXP_TEMPLATE template class xbot_PUBLIC
46 EXP_TEMPLATE template class xbot_PUBLIC
48 EXP_TEMPLATE template class xbot_PUBLIC
50 #endif
51 
52 /*****************************************************************************
53  ** Namespaces
54  *****************************************************************************/
55 
56 namespace xbot {
57 
58 /*****************************************************************************
59  ** Definitions
60  *****************************************************************************/
61 
62 union union_sint16 {
63  short word;
64  unsigned char byte[2];
65 };
66 
67 /*****************************************************************************
68 ** Parent Interface
69 *****************************************************************************/
70 // 串口数据解码程序,使用有限状态机原理
72  public:
73  virtual ~PacketFinder() {}
74  //重定义校验函数
75  bool checkSum();
76 };
77 
78 /*****************************************************************************
79  ** Interface [Xbot]
80  *****************************************************************************/
87  public:
88  Xbot();
89  ~Xbot();
90 
91  /*********************
92  ** Configuration
93  **********************/
94  //初始化
95  void init(Parameters &parameters) throw(ecl::StandardException);
96  bool base_isAlive() const {
97  return base_is_alive;
98  }
100  bool sensor_isAlive() const { return sensor_is_alive; }
101  bool isShutdown() const {
102  return shutdown_requested;
103  }
104  bool isEnabled() const {
105  return is_enabled;
106  }
107  bool enable();
108  bool disable();
109  void shutdown() {
110  shutdown_requested = true;
111  }
112  void resetXbotState();
113  bool is_base_connected() const { return base_is_connected; }
114  bool is_sensor_connected() const { return sensor_is_connected; }
115 
116  /******************************************
117  ** Base Packet Processing
118  *******************************************/
119  //底盘数据流控制程序,运行于base_thread线程中
120  void base_spin();
121  //底盘修复数据段位
122  void base_fixPayload(ecl::PushAndPop<unsigned char> &byteStream);
123 
124  /******************************************
125  ** Sensor Packet Processing
126  *******************************************/
127  //机器上方传感器数据流控制程序,运行于sensor_thread线程中
128  void sensor_spin();
129  //传感器数据段位修复
130  void sensor_fixPayload(ecl::PushAndPop<unsigned char> &byteStream);
131 
132  /******************************************
133  ** Getters - Base Data Protection
134  *******************************************/
135  // 底盘数据锁
136  void base_lockDataAccess();
137  void base_unlockDataAccess();
138 
139  /******************************************
140  ** Getters - Data Protection
141  *******************************************/
142  // 传感器数据锁
143  void sensor_lockDataAccess();
144  void sensor_unlockDataAccess();
145 
146  /******************************************
147  ** Getters - User Friendly Api
148  *******************************************/
149  /* Be sure to lock/unlock the data access (lockDataAccess and
150  * unlockDataAccess)
151  * around any getXXX calls - see the doxygen notes for lockDataAccess. */
152  // 获取机器人朝向,若参数use_imu设置为true,则返回IMU的yaw数据
153  double getHeading() const;
154  // 用于调试数据的显示
155  int getDebugSensors() const;
156  // 获取角速度
157  double getAngularVelocity() const;
158  // 获取水平转台角度
159  unsigned char getYawPlatformDegree() const;
160  // 获取竖直转台角度
161  unsigned char getPitchPlatformDegree() const;
162  // 获取急停开关状态量
163  bool getStopButtonState() const;
164  // 获取电机电源状态
165  bool getPowerState() { return Power; }
166 
167  /******************************************
168  ** Getters - Raw Data Api
169  *******************************************/
170  /* Be sure to lock/unlock the data access (lockDataAccess and
171  * unlockDataAccess)
172  * around any getXXX calls - see the doxygen notes for lockDataAccess. */
173  // 底盘核心数据
174  CoreSensors::Data getCoreSensorData() const { return core_sensors.data; }
175  // 传感器数据
176  Sensors::Data getExtraSensorsData() const { return sensors.data; }
177  /*********************
178  ** Feedback
179  **********************/
180  // 获取关节状态数据,用于ros的state_publisher
181  void getWheelJointStates(float &wheel_left_angle,
182  float &wheel_left_angle_rate,
183  float &wheel_right_angle,
184  float &wheel_right_angle_rate);
185  // 机器人码盘数据计算运动轨迹,用于ros发布odom
186  void updateOdometry(ecl::Pose2D<double> &pose_update,
187  ecl::linear_algebra::Vector3d &pose_update_rates);
188 
189  /*********************
190  ** Soft Commands
191  **********************/
192  void resetOdometry();
193 
194  /*********************
195  ** Hard Commands
196  **********************/
197  //速度控制
198  void setBaseControl(const float &linear_velocity,
199  const float &angular_velocity);
200  //升降控制
201  void setLiftControl(const unsigned char &height_percent);
202  //水平云台控制
203  void setYawPlatformControl(const int &yaw_degree);
204  //竖直云台控制
205  void setPitchPlatformControl(const int &pitch_degree);
206  //电源控制
207  void setPowerControl(const bool &power);
208  //声音控制
209  void setSoundEnableControl(const bool &sound);
210  //状态灯控制
211  void setLedControl(const char &led);
212 
213  //重置机器人
214  void resetXbot();
215 
216  private:
217  /*********************
218  ** Thread
219  **********************/
220  //底盘线程
221  ecl::Thread base_thread;
222  // 传感器线程
223  ecl::Thread sensor_thread;
224  bool shutdown_requested; // helper to shutdown the worker thread.
225 
226  /*********************
227  ** Record RobotState
228  **********************/
229  unsigned char HeightPercent;
230  bool Power;
231 
232  /*********************
233  ** Odometry
234  **********************/
237 
238  /*********************
239  ** Inertia
240  **********************/
241  // 机器人初始化的偏置角
243 
244  /*********************
245  ** Driver Paramters
246  **********************/
248  // 底盘串口是否连接成功
250  // 传感器串口是否连接
252 
253  /*********************
254  ** Acceleration Limiter
255  **********************/
257 
258  /*********************
259  ** Packet Handling
260  **********************/
263  //底盘串口与串口buffer
264  ecl::Serial base_serial;
266  PacketFinder::BufferType base_data_buffer;
267 
268  //传感器串口与buffer
269  ecl::Serial sensor_serial;
271  PacketFinder::BufferType sensor_data_buffer;
272  bool base_is_alive; // used as a flag set by the data stream watchdog
274 
275  /*********************
276  ** Commands
277  **********************/
278  void sendBaseControlCommand();
279  void sendCommand(Command command);
280  ecl::Mutex base_command_mutex; // protection against the user calling the
281  // command functions from multiple threads
282  ecl::Mutex base_data_mutex;
283 
285  ecl::Mutex sensor_data_mutex;
286 
287  Command
288  xbot_command; // used to maintain some state about the command history
290 
291  /*********************
292  ** Signals
293  **********************/
296  ecl::Signal<const std::string &> sig_debug, sig_info, sig_warn, sig_error;
298  // but pushnpop is
299  // not fully
300  // realised yet for
301  // const args in
302  // the formatters.
305  base_sig_raw_data_stream; // should be const, but pushnpop is not fully
306  // realised yet for const args in the
307  // formatters.
309 };
310 
311 } // namespace xbot
312 
313 #endif /* XBOT_HPP_ */
bool sensor_is_alive
Definition: xbot.hpp:273
bool isShutdown() const
Definition: xbot.hpp:101
DiffDrive diff_drive
Definition: xbot.hpp:235
ecl::Serial sensor_serial
Definition: xbot.hpp:269
ecl::Signal< PacketFinder::BufferType & > base_sig_raw_data_stream
Definition: xbot.hpp:305
bool base_is_connected
Definition: xbot.hpp:249
Simple packet finder.
bool Power
Definition: xbot.hpp:230
Parameter list and validator for the xbot.
Definition: parameters.hpp:35
bool is_sensor_connected() const
Definition: xbot.hpp:114
bool is_base_connected() const
Definition: xbot.hpp:113
ecl::Thread base_thread
Definition: xbot.hpp:221
bool base_is_alive
Definition: xbot.hpp:272
bool is_enabled
Definition: xbot.hpp:236
AccelerationLimiter acceleration_limiter
Definition: xbot.hpp:256
double heading_offset
Definition: xbot.hpp:242
Macros for xbot_driver.
#define xbot_PUBLIC
bool sensor_isAlive() const
Definition: xbot.hpp:100
bool isEnabled() const
Definition: xbot.hpp:104
Sensors sensors
Definition: xbot.hpp:262
bool shutdown_requested
Definition: xbot.hpp:224
Command xbot_command
Definition: xbot.hpp:288
ecl::Mutex sensor_command_mutex
Definition: xbot.hpp:284
An acceleration limiter for the xbot.
Standard exception type, provides code location and error string.
bool base_isAlive() const
Definition: xbot.hpp:96
unsigned char HeightPercent
Definition: xbot.hpp:229
ecl::Signal< PacketFinder::BufferType & > sensor_sig_raw_data_stream
Definition: xbot.hpp:308
ecl::Signal sensor_sig_stream_data
Definition: xbot.hpp:295
Convenience header for modules.
Command structure.
Command::Buffer command_buffer
Definition: xbot.hpp:289
CoreSensors::Data getCoreSensorData() const
Definition: xbot.hpp:174
Provides simple packet finder which may be consist of stx, etx, payload, ...
PacketFinder::BufferType base_data_buffer
Definition: xbot.hpp:266
The sigslots connection manager.
Definition: manager.hpp:49
ecl::Thread sensor_thread
Definition: xbot.hpp:223
ecl::Signal< const std::string & > sig_warn
Definition: xbot.hpp:296
PacketFinder::BufferType sensor_data_buffer
Definition: xbot.hpp:271
Parameters parameters
Definition: xbot.hpp:247
ecl::Mutex sensor_data_mutex
Definition: xbot.hpp:285
bool getPowerState()
Definition: xbot.hpp:165
ecl::Signal base_sig_stream_data
Definition: xbot.hpp:294
virtual ~PacketFinder()
Definition: xbot.hpp:73
ecl::Mutex base_data_mutex
Definition: xbot.hpp:282
CoreSensors core_sensors
Definition: xbot.hpp:261
void shutdown()
Definition: xbot.hpp:109
ecl::Signal< Command::Buffer & > sensor_sig_raw_data_command
Definition: xbot.hpp:303
ecl::Serial base_serial
Definition: xbot.hpp:264
Packets convenience header.
Signalling component of a callback system.
Definition: signal.hpp:47
ecl::Mutex base_command_mutex
Definition: xbot.hpp:280
PacketFinder base_packet_finder
Definition: xbot.hpp:265
Definition: command.hpp:30
Parameter configuration for the xbot.
bool sensor_is_connected
Definition: xbot.hpp:251
#define EXP_TEMPLATE
The core xbot driver class.
Definition: xbot.hpp:86
PacketFinder sensor_packet_finder
Definition: xbot.hpp:270
ecl::Signal< Command::Buffer & > base_sig_raw_data_command
Definition: xbot.hpp:297
Sensors::Data getExtraSensorsData() const
Definition: xbot.hpp:176


xbot_driver
Author(s): Roc, wangpeng@droid.ac.cn
autogenerated on Sat Oct 10 2020 03:27:38