dock_drive.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 ** defines
42 *****************************************************************************/
43 
44 #define sign(x) (x>0?+1:x<0?-1:0)
45 #define stringfy(x) #x
46 #define setState(x) {state=x;}
47 #define setStateVel(x,v,w) {setState(x);setVel(v,w);}
48 
49 /*****************************************************************************
50 ** Namespaces
51 *****************************************************************************/
52 
53 namespace kobuki {
54 
55 /*****************************************************************************
56 ** Implementation
57 *****************************************************************************/
59  is_enabled(false)
60  , can_run(false)
61  , state(RobotDockingState::IDLE), state_str("IDLE")
62  , vx(0.0), wz(0.0)
63  , signal_window(20)
64  , bump_remainder(0)
65  , dock_stabilizer(0)
66  , dock_detector(0)
67  , rotated(0.0)
68  , min_abs_v(0.01)
69  , min_abs_w(0.1)
70  , ROBOT_STATE_STR(13)
71 {
72  // Debug messages
73  ROBOT_STATE_STR[0] = "IDLE";
74  ROBOT_STATE_STR[1] = "DONE";
75  ROBOT_STATE_STR[2] = "DOCKED_IN";
76  ROBOT_STATE_STR[3] = "BUMPED_DOCK";
77  ROBOT_STATE_STR[4] = "BUMPED";
78  ROBOT_STATE_STR[5] = "SCAN";
79  ROBOT_STATE_STR[6] = "FIND_STREAM";
80  ROBOT_STATE_STR[7] = "GET_STREAM";
81  ROBOT_STATE_STR[8] = "ALIGNED";
82  ROBOT_STATE_STR[9] = "ALIGNED_FAR";
83  ROBOT_STATE_STR[10] = "ALIGNED_NEAR";
84  ROBOT_STATE_STR[11] = "UNKNOWN";
85  ROBOT_STATE_STR[12] = "LOST";
86 }
87 
89 
90 void DockDrive::setVel(double v, double w)
91 {
92  vx = sign(v) * std::max(std::abs(v), min_abs_v);
93  wz = sign(w) * std::max(std::abs(w), min_abs_w);
94 }
95 
96 void DockDrive::modeShift(const std::string& mode)
97 {
98  if (mode == "enable") { is_enabled = true; can_run = true; state = RobotDockingState::IDLE;}
99  if (mode == "disable") { is_enabled = false; can_run = false; }
100  if (mode == "run") can_run = true;
101  if (mode == "stop") can_run = false;
102 }
103 
104 
115 void DockDrive::update(const std::vector<unsigned char> &signal
116  , const unsigned char &bumper
117  , const unsigned char &charger
118  , const ecl::LegacyPose2D<double>& pose) {
119 
120  ecl::LegacyPose2D<double> pose_update;
121  std::vector<unsigned char> signal_filt(signal.size(), 0);
122  std::string debug_str;
123 
124  // process bumper and charger event first
125  // docking algorithm terminates here
126  if(bumper || charger) {
127  processBumpChargeEvent(bumper, charger);
128  }
129  else {
130  computePoseUpdate(pose_update, pose);
131  filterIRSensor(signal_filt, signal);
132  updateVelocity(signal_filt, pose_update, debug_str);
133  }
134 
136 
137  // for easy debugging
138  generateDebugMessage(signal_filt, bumper, charger, pose_update, debug_str);
139 
140  return;
141 }
142 
150 {
151  double dx = pose.x() - pose_priv.x();
152  double dy = pose.y() - pose_priv.y();
153  pose_update.x( std::sqrt( dx*dx + dy*dy ) );
154  pose_update.heading( pose.heading() - pose_priv.heading() );
155  //std::cout << pose_diff << "=" << pose << "-" << pose_priv << " | " << pose_update << std::endl;
156  pose_priv = pose;
157 
158 }
159 
160 
168 void DockDrive::filterIRSensor(std::vector<unsigned char>& signal_filt,const std::vector<unsigned char> &signal)
169 {
170  //dock_ir signals filtering
171  past_signals.push_back(signal);
172  while (past_signals.size() > signal_window) {
173  past_signals.erase( past_signals.begin(), past_signals.begin() + past_signals.size() - signal_window);
174  }
175 
176  for ( unsigned int i = 0; i < past_signals.size(); i++) {
177  if (signal_filt.size() != past_signals[i].size())
178  continue;
179  for (unsigned int j = 0; j < signal_filt.size(); j++)
180  signal_filt[j] |= past_signals[i][j];
181  }
182 }
183 
184 
185 void DockDrive::velocityCommands(const double &vx_, const double &wz_) {
186  // vx: in m/s
187  // wz: in rad/s
188  vx = vx_;
189  wz = wz_;
190 }
191 
192 /****************************************************
193  * @brief process bumper and charge event. If robot is charging, terminates auto dokcing process. If it bumps something, Set the next state as bumped and go backward
194  *
195  * @bumper - indicates whether bumper has pressed
196  * @charger - indicates whether robot is charging
197  *
198  ****************************************************/
199 void DockDrive::processBumpChargeEvent(const unsigned char& bumper, const unsigned char& charger) {
201  if(charger && bumper) {
202  new_state = RobotDockingState::BUMPED_DOCK;
203  setStateVel(new_state, -0.01, 0.0);
204  }
205  else if(charger) {
206  if(dock_stabilizer++ == 0) {
207  new_state = RobotDockingState::DOCKED_IN;
208  setStateVel(new_state, 0.0, 0.0);
209  }
210  else if(dock_stabilizer > 20) {
211  dock_stabilizer = 0;
212  is_enabled = false;
213  can_run = false;
214  new_state = RobotDockingState::DONE;
215  setStateVel(new_state, 0.0, 0.0);
216  }
217  else {
218  new_state = RobotDockingState::DOCKED_IN;
219  setStateVel(new_state, 0.0, 0.0);
220  }
221  }
222  else if(bumper) {
223  new_state = RobotDockingState::BUMPED;
224  setStateVel(new_state, -0.05, 0.0);
225  bump_remainder = 0;
226  }
227  state_str = ROBOT_STATE_STR[new_state];
228 }
229 
230 /*************************
231  * @breif processing. algorithms; transforma to velocity command
232  *
233  * @param dock_ir signal
234  * @param bumper sensor
235  * @param charger sensor
236  * @param pose_update
237  *
238  *************************/
239 void DockDrive::updateVelocity(const std::vector<unsigned char>& signal_filt, const ecl::LegacyPose2D<double>& pose_update, std::string& debug_str)
240 {
241  std::ostringstream oss;
242  RobotDockingState::State current_state, new_state;
243  double new_vx = 0.0;
244  double new_wz = 0.0;
245 
246  // determine the current state based on ir and the previous state
247  // common transition. idle -> scan -> find_stream -> get_stream -> scan -> aligned_far -> aligned_near -> docked_in -> done
248 
249  current_state = new_state = state;
250  switch((unsigned int)current_state) {
252  idle(new_state, new_vx, new_wz);
253  break;
255  scan(new_state, new_vx, new_wz, signal_filt, pose_update, debug_str);
256  break;
258  find_stream(new_state, new_vx, new_wz, signal_filt);
259  break;
261  get_stream(new_state, new_vx, new_wz, signal_filt);
262  break;
266  aligned(new_state, new_vx, new_wz, signal_filt, debug_str);
267  break;
269  bumped(new_state, new_vx, new_wz, bump_remainder);
270  break;
271  default:
272  oss << "Wrong state : " << current_state;
273  debug_str = oss.str();
274  break;
275  }
276 
277  setStateVel(new_state, new_vx, new_wz);
278  state_str = ROBOT_STATE_STR[new_state];
279 }
280 
281 /*************************
282  * @breif Check if any ir sees the given state signal from dock station
283  *
284  * @param filtered signal
285  * @param dock ir state
286  *
287  * @ret true or false
288  *************************/
289 bool DockDrive::validateSignal(const std::vector<unsigned char>& signal_filt, const unsigned int state)
290 {
291  unsigned int i;
292  for(i = 0; i < signal_filt.size(); i++)
293  {
294  if(signal_filt[i] & state)
295  return true;
296  }
297  return false;
298 }
299 
300 } // kobuki namespace
void processBumpChargeEvent(const unsigned char &bumper, const unsigned char &charger)
Definition: dock_drive.cpp:199
void computePoseUpdate(ecl::LegacyPose2D< double > &pose_update, const ecl::LegacyPose2D< double > &pose)
compute pose update from previouse pose and current pose
Definition: dock_drive.cpp:149
unsigned int signal_window
Definition: dock_drive.hpp:138
void modeShift(const std::string &mode)
Definition: dock_drive.cpp:96
RobotDockingState::State state
Definition: dock_drive.hpp:134
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 setVel(double v, double w)
Definition: dock_drive.cpp:90
#define sign(x)
Definition: dock_drive.cpp:44
void idle(RobotDockingState::State &state, double &vx, double &wz)
#define setStateVel(x, v, w)
Definition: dock_drive.cpp:47
std::vector< std::string > ROBOT_STATE_STR
Definition: dock_drive.hpp:152
void filterIRSensor(std::vector< unsigned char > &signal_filt, const std::vector< unsigned char > &signal)
Definition: dock_drive.cpp:168
void updateVelocity(const std::vector< unsigned char > &signal_filt, const ecl::LegacyPose2D< double > &pose_update, std::string &debug_str)
Definition: dock_drive.cpp:239
std::vector< std::vector< unsigned char > > past_signals
Definition: dock_drive.hpp:137
bool validateSignal(const std::vector< unsigned char > &signal_filt, const unsigned int state)
Definition: dock_drive.cpp:289
std::string state_str
Definition: dock_drive.hpp:135
void generateDebugMessage(const std::vector< unsigned char > &signal_filt, const unsigned char &bumper, const unsigned char &charger, const ecl::LegacyPose2D< double > &pose_update, const std::string &debug_str)
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)
void velocityCommands(const double &vx, const double &wz)
Definition: dock_drive.cpp:185
ecl::LegacyPose2D< double > pose_priv
Definition: dock_drive.hpp:145
void update(const std::vector< unsigned char > &signal, const unsigned char &bumper, const unsigned char &charger, const ecl::LegacyPose2D< double > &pose)
Updates the odometry from firmware stamps and encoders.
Definition: dock_drive.cpp:115


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