dock_drive_states.cpp
Go to the documentation of this file.
1 /*
2  * copyright (c) 2013, Yujin Robot.
3  * all rights reserved.
4  *
5  * redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * neither the name of yujin robot nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * this software is provided by the copyright holders and contributors "as is"
18  * and any express or implied warranties, including, but not limited to, the
19  * implied warranties of merchantability and fitness for a particular purpose
20  * are disclaimed. in no event shall the copyright owner or contributors be
21  * liable for any direct, indirect, incidental, special, exemplary, or
22  * consequential damages (including, but not limited to, procurement of
23  * substitute goods or services; loss of use, data, or profits; or business
24  * interruption) however caused and on any theory of liability, whether in
25  * contract, strict liability, or tort (including negligence or otherwise)
26  * arising in any way out of the use of this software, even if advised of the
27  * possibility of such damage.
28  */
34 /*****************************************************************************
35 ** includes
36 *****************************************************************************/
37 
39 
40 /*****************************************************************************
41 ** Namespaces
42 *****************************************************************************/
43 
44 namespace kobuki {
45  /*********************************************************
46  * Shared variables among states
47  * @ dock_detector : records + or - when middle IR sensor detects docking signal
48  * @ rotated : records how much the robot has rotated in scan state
49  * @ bump_remainder : from processBumpChargerEvent.
50  *********************************************************/
51 
52 
53  /*******************************************************
54  * Idle
55  * @breif Entry of auto docking state machine
56  *
57  * Shared variable
58  * @dock_detecotr - indicates where the dock is located. Positive means dock is on left side of robot
59  * @rotated - indicates how much the robot has rotated while scan
60  *******************************************************/
61  void DockDrive::idle(RobotDockingState::State& nstate,double& nvx, double& nwz) {
62  dock_detector = 0;
63  rotated = 0.0;
64  nstate = RobotDockingState::SCAN;
65  nvx = 0;
66  nwz = 0.66;
67  }
68 
69  /********************************************************
70  * Scan
71  * @breif While it rotates ccw, determines the dock location with only middle sensor.
72  * If its middle sensor detects center ir, the robot is aligned with docking station
73  *
74  * Shared variable
75  * @dock_detecotr - indicates where the dock is located. Positive means dock is on left side of robot
76  * @rotated - indicates how much the robot has rotated while scan
77  ********************************************************/
78  void DockDrive::scan(RobotDockingState::State& nstate,double& nvx, double& nwz, const std::vector<unsigned char>& signal_filt, const ecl::LegacyPose2D<double>& pose_update, std::string& debug_str) {
79  unsigned char mid = signal_filt[1];
80 
81  RobotDockingState::State next_state;
82  double next_vx;
83  double next_wz;
84 
85  rotated += pose_update.heading() / (2.0 * M_PI);
86  std::ostringstream oss;
87  oss << "rotated: " << std::fixed << std::setprecision(2) << std::setw(4) << rotated;
88  debug_str = oss.str();
89 
90 
91 
93  {
94  next_state = RobotDockingState::ALIGNED;
95  next_vx = 0.05;
96  next_wz = 0.0;
97  }
98  // robot is located left side of dock
100  {
101  dock_detector--;
102  next_state = RobotDockingState::SCAN;
103  next_vx = 0.0;
104  next_wz = 0.66;
105  }
106  // robot is located right side of dock
108  {
109  dock_detector++;
110  next_state = RobotDockingState::SCAN;
111  next_vx = 0.0;
112  next_wz = 0.66;
113  }
114  // robot is located in front of robot
115  else if(mid) { // if mid sensor sees something, rotate slowly
116  next_state = RobotDockingState::SCAN;
117  next_vx = 0.0;
118  next_wz = 0.10;
119  }
120  else if(std::abs(rotated) > 1.0)
121  {
122  next_state = RobotDockingState::FIND_STREAM;
123  next_vx = 0;
124  next_wz = 0;
125  }
126  else { // if mid sensor does not see anything, rotate fast
127  next_state = RobotDockingState::SCAN;
128  next_vx = 0.0;
129  next_wz = 0.66;
130  }
131 
132  nstate = next_state;
133  nvx = next_vx;
134  nwz = next_wz;
135  }
136 
137  /********************************************************
138  * Find stream
139  * @breif based on dock_detector variable, it determines the dock's location and rotates toward the center line of dock
140  *
141  * Shared variable
142  * @dock_detector - to determine dock's location
143  *
144  ********************************************************/
145  void DockDrive::find_stream(RobotDockingState::State& nstate,double& nvx, double& nwz, const std::vector<unsigned char>& signal_filt) {
146  unsigned char right = signal_filt[0];
147  unsigned char left = signal_filt[2];
149  double next_vx = 0.0;
150  double next_wz = 0.0;
151 
152  if(dock_detector > 0) // robot is located in right side of dock
153  {
154  // turn right, CW until get right signal from left sensor
156  next_state = RobotDockingState::GET_STREAM;
157  next_vx = 0.5;
158  next_wz = 0.0;
159  }
160  else {
161  next_state = RobotDockingState::FIND_STREAM;
162  next_vx = 0.0;
163  next_wz = -0.33;
164  }
165  }
166  else if(dock_detector < 0 ) // robot is located in left side of dock
167  {
168  // turn left, CCW until get left signal from right sensor
170  {
171  next_state = RobotDockingState::GET_STREAM;
172  next_vx = 0.5;
173  next_wz = 0.0;
174  }
175  else {
176  next_state = RobotDockingState::FIND_STREAM;
177  next_vx = 0.0;
178  next_wz = 0.33;
179  }
180  }
181 
182  nstate = next_state;
183  nvx = next_vx;
184  nwz = next_wz;
185  }
186 
187  /********************************************************
188  * Get stream
189  * @brief In this state, robot is heading the center line of dock. When it passes the center, it rotates toward the dock
190  *
191  * Shared Variable
192  * @ dock_detector - reset
193  * @ rotated - reset
194  ********************************************************/
195  void DockDrive::get_stream(RobotDockingState::State& nstate,double& nvx, double& nwz, const std::vector<unsigned char>& signal_filt)
196  {
197  unsigned char right = signal_filt[0];
198  unsigned char left = signal_filt[2];
200  double next_vx = 0.0;
201  double next_wz = 0.0;
202 
203  if(dock_detector > 0) { // robot is located in right side of dock
205  dock_detector = 0;
206  rotated = 0;
207  next_state = RobotDockingState::SCAN;
208  next_vx = 0;
209  next_wz = 0.1;
210  }
211  else {
212  next_state = RobotDockingState::GET_STREAM;
213  next_vx = 0.05;
214  next_wz = 0.0;
215  }
216  }
217  else if(dock_detector < 0) { // robot is located left side of dock
219  dock_detector = 0;
220  rotated = 0;
221  next_state = RobotDockingState::SCAN;
222  next_vx = 0;
223  next_wz = 0.1;
224  }
225  else {
226  next_state = RobotDockingState::GET_STREAM;
227  next_vx = 0.05;
228  next_wz = 0.0;
229  }
230  }
231 
232  nstate = next_state;
233  nvx = next_vx;
234  nwz = next_wz;
235  }
236 
237 
238  /********************************************************
239  * Aligned
240  * @breif Robot sees center IR with middle sensor. It is heading dock. It approaches to the dock only using mid sensor
241  *
242  * Shared Variable
243  * @ dock_detector - reset
244  * @ rotated - reset
245  ********************************************************/
246  void DockDrive::aligned(RobotDockingState::State& nstate,double& nvx, double& nwz, const std::vector<unsigned char>& signal_filt, std::string& debug_str)
247  {
248  unsigned char mid = signal_filt[1];
249  RobotDockingState::State next_state = nstate;
250  double next_vx = nvx;
251  double next_wz = nwz;
252 
253  if(mid)
254  {
255  if(((mid & DockStationIRState::NEAR) == DockStationIRState::NEAR_CENTER) || ((mid & DockStationIRState::NEAR) == DockStationIRState::NEAR))
256  {
257  debug_str = "AlignedNearCenter";
258  next_state = RobotDockingState::ALIGNED_NEAR;
259  next_vx = 0.05;
260  next_wz = 0.0;
261  }
262  else if(mid & DockStationIRState::NEAR_LEFT) {
263  debug_str = "AlignedNearLeft";
264  next_state = RobotDockingState::ALIGNED_NEAR;
265  next_vx = 0.05;
266  next_wz = 0.1;
267  }
268  else if(mid & DockStationIRState::NEAR_RIGHT) {
269  debug_str = "AlignedNearRight";
270  next_state = RobotDockingState::ALIGNED_NEAR;
271  next_vx = 0.05;
272  next_wz = -0.1;
273  }
274  else if(((mid & DockStationIRState::FAR) == DockStationIRState::FAR_CENTER) || ((mid & DockStationIRState::FAR) == DockStationIRState::FAR)) {
275  debug_str = "AlignedFarCenter";
276  next_state = RobotDockingState::ALIGNED_FAR;
277  next_vx = 0.1;
278  next_wz = 0.0;
279  }
280  else if(mid & DockStationIRState::FAR_LEFT) {
281  debug_str = "AlignedFarLeft";
282  next_state = RobotDockingState::ALIGNED_FAR;
283  next_vx = 0.1;
284  next_wz = 0.3;
285  }
286  else if(mid & DockStationIRState::FAR_RIGHT) {
287  debug_str = "AlignedFarRight";
288  next_state = RobotDockingState::ALIGNED_FAR;
289  next_vx = 0.1;
290  next_wz = -0.3;
291  }
292  else {
293  dock_detector = 0;
294  rotated = 0.0;
295  next_state = RobotDockingState::SCAN;
296  next_vx = 0.0;
297  next_wz = 0.66;
298  }
299  }
300  else {
301  next_state = RobotDockingState::SCAN;
302  next_vx = 0.0;
303  next_wz = 0.66;
304  }
305 
306  nstate = next_state;
307  nvx = next_vx;
308  nwz = next_wz;
309  }
310 
311 
312  /********************************************************
313  * Bumped
314  * @breif Robot has bumped somewhere. Go backward for 10 iteration
315  *
316  ********************************************************/
317  void DockDrive::bumped(RobotDockingState::State& nstate,double& nvx, double& nwz, int& bump_count)
318  {
319  if(bump_count < 10)
320  {
321  nvx = -0.05;
322  nwz = 0.0;
323  bump_count++;
324  }
325  else {
326  nstate = RobotDockingState::SCAN;
327  nvx = 0.0;
328  nwz = 0.0;
329  bump_count = 0;
330  }
331 
332  }
333 }
Simple module for the docking drive algorithm.
void bumped(RobotDockingState::State &nstate, double &nvx, double &nwz, int &bump_count)
void scan(RobotDockingState::State &state, double &vx, double &wz, const std::vector< unsigned char > &signal_filt, const ecl::LegacyPose2D< double > &pose_update, std::string &debug_str)
void find_stream(RobotDockingState::State &state, double &vx, double &wz, const std::vector< unsigned char > &signal_filt)
void idle(RobotDockingState::State &state, double &vx, double &wz)
void get_stream(RobotDockingState::State &state, double &vx, double &wz, const std::vector< unsigned char > &signal_filt)
std::string debug_str
Definition: dock_drive.hpp:135
void aligned(RobotDockingState::State &state, double &vx, double &wz, const std::vector< unsigned char > &signal_filt, std::string &debug_str)


kobuki_dock_drive
Author(s): Younghun Ju
autogenerated on Fri Sep 18 2020 03:22:00