RobotOperator.cpp
Go to the documentation of this file.
1 #include <nav_msgs/GridCells.h>
2 #include <math.h>
3 
5 
6 #define PI 3.14159265
7 
9 {
10  // Create the local costmap
13 
14  // Publish / subscribe to ROS topics
15  ros::NodeHandle robotNode;
16  robotNode.param("robot_frame", mRobotFrame, std::string("robot"));
17  robotNode.param("odometry_frame", mOdometryFrame, std::string("odometry_base"));
19  mControlPublisher = robotNode.advertise<geometry_msgs::Twist>(CONTROL_TOPIC, 1);
20  mCostPublisher = robotNode.advertise<geometry_msgs::Vector3>("costs", 1);
21 
22  // Get parameters from the parameter server
23  ros::NodeHandle operatorNode("~/");
24  operatorNode.param("publish_route", mPublishRoute, false);
25  if(mPublishRoute)
26  {
27  ROS_INFO("Will publish desired direction on '%s' and control direction on '%s'.", ROUTE_TOPIC, PLAN_TOPIC);
28  mTrajectoryPublisher = operatorNode.advertise<nav_msgs::GridCells>(ROUTE_TOPIC, 1);
29  mPlanPublisher = operatorNode.advertise<nav_msgs::GridCells>(PLAN_TOPIC, 1);
30  }
31  operatorNode.param("max_free_space", mMaxFreeSpace, 5.0);
32  operatorNode.param("safety_decay", mSafetyDecay, 0.95);
33  operatorNode.param("safety_weight", mSafetyWeight, 1);
34  operatorNode.param("conformance_weight", mConformanceWeight, 1);
35  operatorNode.param("continue_weight", mContinueWeight, 1);
36  operatorNode.param("escape_weight", mEscapeWeight, 1);
37  operatorNode.param("max_velocity", mMaxVelocity, 1.0);
38 
39  // Apply tf_prefix to all used frame-id's
42 
43  // Initialize the lookup table for the driving directions
44  ROS_INFO("Initializing LUT...");
45  initTrajTable();
46  ROS_INFO("...done!");
47 
48  // Set internal parameters
50  mDesiredVelocity = 0;
52  mCurrentVelocity = 0;
53  mDriveMode = 0;
54  mRecoverySteps = 0;
55 }
56 
58 {
59  for(int i = 0; i < LUT_RESOLUTION; i++)
60  {
61  delete mTrajTable[i];
62  }
63 }
64 
66 {
67  for(int i = 0; i < (LUT_RESOLUTION * 4) + 2; i++)
68  {
69  mTrajTable[i] = NULL;
70  }
71  for(int i = 1; i < LUT_RESOLUTION; i++)
72  {
73  double tw = -PI * i / LUT_RESOLUTION;
74  double tx = cos(tw) + 1;
75  double ty = -sin(tw);
76  double tr = ((tx*tx)+(ty*ty))/(ty+ty);
77  std::vector<geometry_msgs::Point32> points;
78  double alpha = 0;
79  while(alpha < PI)
80  {
81  double x = tr * sin(alpha);
82  double y = tr * (1.0 - cos(alpha));
83  geometry_msgs::Point32 p;
84  p.x = x;
85  p.y = y;
86  p.z = 0;
87  points.push_back(p);
88  alpha += mRasterSize / tr;
89  }
90  // Add the PointCloud to the LUT
91  // Circle in forward-left direction
92  sensor_msgs::PointCloud* flcloud = new sensor_msgs::PointCloud();
93  flcloud->header.stamp = ros::Time(0);
94  flcloud->header.frame_id = mRobotFrame;
95  flcloud->points.resize(points.size());
96 
97  // Circle in forward-right direction
98  sensor_msgs::PointCloud* frcloud = new sensor_msgs::PointCloud();
99  frcloud->header.stamp = ros::Time(0);
100  frcloud->header.frame_id = mRobotFrame;
101  frcloud->points.resize(points.size());
102 
103  // Circle in backward-left direction
104  sensor_msgs::PointCloud* blcloud = new sensor_msgs::PointCloud();
105  blcloud->header.stamp = ros::Time(0);
106  blcloud->header.frame_id = mRobotFrame;
107  blcloud->points.resize(points.size());
108 
109  // Circle in backward-right direction
110  sensor_msgs::PointCloud* brcloud = new sensor_msgs::PointCloud();
111  brcloud->header.stamp = ros::Time(0);
112  brcloud->header.frame_id = mRobotFrame;
113  brcloud->points.resize(points.size());
114 
115  for(unsigned int j = 0; j < points.size(); j++)
116  {
117  flcloud->points[j] = points[j];
118  frcloud->points[j] = points[j];
119  blcloud->points[j] = points[j];
120  brcloud->points[j] = points[j];
121 
122  frcloud->points[j].y *= -1;
123  blcloud->points[j].x *= -1;
124  brcloud->points[j].x *= -1;
125  brcloud->points[j].y *= -1;
126  }
127  mTrajTable[LUT_RESOLUTION - i] = flcloud;
128  mTrajTable[LUT_RESOLUTION + i] = frcloud;
129  mTrajTable[(3 * LUT_RESOLUTION + 1) - i] = blcloud;
130  mTrajTable[(3 * LUT_RESOLUTION + 1) + i] = brcloud;
131  }
132 
133  // Add First and Last LUT-element
134  geometry_msgs::Point32 p;
135  p.x = 0;
136  p.y = 0;
137  p.z = 0;
138 
139  sensor_msgs::PointCloud* turn = new sensor_msgs::PointCloud();
140  turn->header.stamp = ros::Time(0);
141  turn->header.frame_id = mRobotFrame;
142  turn->points.resize(1);
143  turn->points[0] = p;
144 
145  int straight_len = 5.0 / mRasterSize;
146 
147  sensor_msgs::PointCloud* fscloud = new sensor_msgs::PointCloud();
148  fscloud->header.stamp = ros::Time(0);
149  fscloud->header.frame_id = mRobotFrame;
150  fscloud->points.resize(straight_len);
151 
152  sensor_msgs::PointCloud* bscloud = new sensor_msgs::PointCloud();
153  bscloud->header.stamp = ros::Time(0);
154  bscloud->header.frame_id = mRobotFrame;
155  bscloud->points.resize(straight_len);
156 
157  for(int i = 0; i < straight_len; i++)
158  {
159  fscloud->points[i] = p;
160  bscloud->points[i] = p;
161  bscloud->points[i].x *= -1;
162  p.x += mRasterSize;
163  }
164 
165  mTrajTable[LUT_RESOLUTION] = fscloud;
166  mTrajTable[LUT_RESOLUTION*3 + 1] = bscloud;
167 
168  mTrajTable[0] = turn;
169  mTrajTable[LUT_RESOLUTION*2] = turn;
170  mTrajTable[LUT_RESOLUTION*2 + 1] = turn;
171  mTrajTable[LUT_RESOLUTION*4 + 1] = turn;
172 
173  for(int i = 0; i < (LUT_RESOLUTION * 4) + 2; i++)
174  {
175  if(!mTrajTable[i])
176  {
177  ROS_ERROR("Table entry %d has not been initialized!", i);
178  }
179  }
180 }
181 
182 void RobotOperator::receiveCommand(const nav2d_operator::cmd::ConstPtr& msg)
183 {
184  if(msg->Turn < -1 || msg->Turn > 1)
185  {
186  // The given direction is invalid.
187  // Something is going wrong, so better stop the robot:
188  mDesiredDirection = 0;
189  mDesiredVelocity = 0;
190  mCurrentDirection = 0;
191  mCurrentVelocity = 0;
192  ROS_ERROR("Invalid turn direction on topic '%s'!", COMMAND_TOPIC);
193  return;
194  }
195  mDesiredDirection = msg->Turn;
196  mDesiredVelocity = msg->Velocity * mMaxVelocity;
197  mDriveMode = msg->Mode;
198 }
199 
201 {
202  // 1. Get a copy of the costmap to work on.
204  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(mCostmap->getMutex()));
205  double bestDirection, d;
206 
207  // 2. Set velocity and direction depending on drive mode
208  switch(mDriveMode)
209  {
210  case 0:
211  bestDirection = findBestDirection();
212  d = bestDirection - mCurrentDirection;
213  if(d < -0.2) d = -0.2;
214  if(d > 0.2) d = 0.2;
215  mCurrentDirection += d;
217  break;
218  case 1:
219  mCurrentDirection = mDesiredDirection;
221  break;
222  default:
223  ROS_ERROR("Invalid drive mode!");
224  mCurrentVelocity = 0.0;
225  }
226 
227  // Create some Debug-Info
229 
230  sensor_msgs::PointCloud* originalCloud = getPointCloud(mCurrentDirection, mDesiredVelocity);
231  sensor_msgs::PointCloud transformedCloud;
232 
233  try
234  {
235  mTfListener.transformPointCloud(mOdometryFrame,*originalCloud,transformedCloud);
236  }
237  catch(tf::TransformException ex)
238  {
239  ROS_ERROR("%s", ex.what());
240  return;
241  }
242 
243  // Determine maximum linear velocity
244  int freeCells = calculateFreeSpace(&transformedCloud);
245  double freeSpace = mRasterSize * freeCells;
246 
247  double safeVelocity = (freeSpace / mMaxFreeSpace) + 0.05;
248  if(freeCells == transformedCloud.points.size() && safeVelocity < 0.5)
249  safeVelocity = 0.5;
250 
251  if(freeSpace < 0.3 && freeCells < transformedCloud.points.size())
252  safeVelocity = 0;
253 
254  if(safeVelocity > mMaxVelocity)
255  safeVelocity = mMaxVelocity;
256 
257  // Check whether the robot is stuck
258  if(mRecoverySteps > 0) mRecoverySteps--;
259  if(safeVelocity < 0.1)
260  {
261  if(mDriveMode == 0)
262  {
263  mRecoverySteps = 30; // Recover for 3 seconds
264  ROS_WARN_THROTTLE(1, "Robot is stuck! Trying to recover...");
265  }else
266  {
267  mCurrentVelocity = 0;
268  ROS_WARN_THROTTLE(1, "Robot cannot move further in this direction!");
269  }
270  }
271 
272  // Publish route via ROS (mainly for debugging)
273  if(mPublishRoute)
274  {
275  nav_msgs::GridCells route_msg;
276  route_msg.header.frame_id = mOdometryFrame;
277  route_msg.header.stamp = ros::Time::now();
278 
279  route_msg.cell_width = mCostmap->getResolution();
280  route_msg.cell_height = mCostmap->getResolution();
281 
282  route_msg.cells.resize(freeCells);
283  for(int i = 0; i < freeCells; i++)
284  {
285  route_msg.cells[i].x = transformedCloud.points[i].x;
286  route_msg.cells[i].y = transformedCloud.points[i].y;
287  route_msg.cells[i].z = transformedCloud.points[i].z;
288  }
289  mTrajectoryPublisher.publish(route_msg);
290 
291  // Publish plan via ROS (mainly for debugging)
292  sensor_msgs::PointCloud* originalPlanCloud = getPointCloud(mDesiredDirection, mDesiredVelocity);
293  sensor_msgs::PointCloud transformedPlanCloud;
294 
295  try
296  {
297  mTfListener.transformPointCloud(mOdometryFrame,*originalPlanCloud,transformedPlanCloud);
298  }
299  catch(tf::TransformException ex)
300  {
301  ROS_ERROR("%s", ex.what());
302  return;
303  }
304  nav_msgs::GridCells plan_msg;
305  plan_msg.header = route_msg.header;
306 
307  plan_msg.cell_width = mCostmap->getResolution();
308  plan_msg.cell_height = mCostmap->getResolution();
309 
310  int freeSpacePlan = calculateFreeSpace(&transformedPlanCloud);
311  plan_msg.cells.resize(freeSpacePlan);
312  for(int i = 0; i < freeSpacePlan; i++)
313  {
314  plan_msg.cells[i].x = transformedPlanCloud.points[i].x;
315  plan_msg.cells[i].y = transformedPlanCloud.points[i].y;
316  plan_msg.cells[i].z = transformedPlanCloud.points[i].z;
317  }
318  mPlanPublisher.publish(plan_msg);
319  }
320 
321  // Publish result via Twist-Message
322  geometry_msgs::Twist controlMsg;
323  double velocity = mCurrentVelocity;
324  if(mCurrentDirection == 0)
325  {
326  if(velocity > safeVelocity)
327  {
328  ROS_DEBUG("Desired velocity of %.2f is limited to %.2f", velocity, safeVelocity);
329  velocity = safeVelocity;
330  }else if(velocity < -safeVelocity)
331  {
332  ROS_DEBUG("Desired velocity of %.2f is limited to %.2f", velocity, -safeVelocity);
333  velocity = -safeVelocity;
334  }
335  controlMsg.linear.x = velocity;
336  controlMsg.angular.z = 0;
337  }else if(mCurrentDirection == -1 || mCurrentDirection == 1)
338  {
339  controlMsg.linear.x = 0;
340  controlMsg.angular.z = -1.0 * mCurrentDirection * velocity;
341  }else
342  {
343  double x = sin(mCurrentDirection * PI);
344  double y = (cos(mCurrentDirection * PI) + 1);
345  double r = ((x*x) + (y*y)) / (2*x);
346  double abs_r = (r > 0) ? r : -r;
347  velocity /= (1 + (1.0/abs_r));
348  if(velocity > safeVelocity)
349  {
350  ROS_DEBUG("Desired velocity of %.2f is limited to %.2f", velocity, safeVelocity);
351  velocity = safeVelocity;
352  }else if(velocity < -safeVelocity)
353  {
354  ROS_DEBUG("Desired velocity of %.2f is limited to %.2f", velocity, -safeVelocity);
355  velocity = -safeVelocity;
356  }
357 
358  controlMsg.linear.x = velocity;
359  controlMsg.angular.z = -1.0 / r * controlMsg.linear.x;
360  }
361  mControlPublisher.publish(controlMsg);
362 }
363 
364 int RobotOperator::calculateFreeSpace(sensor_msgs::PointCloud* cloud)
365 {
366  unsigned int mx, my;
367  int length = cloud->points.size();
368  int freeSpace = 0;
369  for(int i = 0; i < length; i++)
370  {
371  if(mCostmap->worldToMap(cloud->points[i].x, cloud->points[i].y, mx, my))
372  {
374  {
375  freeSpace++;
376  }else
377  {
378  break;
379  }
380  }else
381  {
382  break;
383  }
384  }
385  return freeSpace;
386 }
387 
388 double RobotOperator::evaluateAction(double direction, double velocity, bool debug)
389 {
390  sensor_msgs::PointCloud* originalCloud = getPointCloud(direction, velocity);
391  sensor_msgs::PointCloud transformedCloud;
392  try
393  {
394  mTfListener.transformPointCloud(mOdometryFrame, *originalCloud,transformedCloud);
395  }
396  catch(tf::TransformException ex)
397  {
398  ROS_ERROR("%s", ex.what());
399  return 1;
400  }
401 
402  double valueSafety = 0.0; // How safe is it to move in that direction?
403  double valueEscape = 0.0; // How much does the safety improve?
404  double valueConformance = 0.0; // How conform is it with the desired direction?
405  double valueContinue = 0.0; // How conform is it with the previous command?
406 
407  double decay = 1.0;
408  double safe_max = 0.0;
409  double cost_max = 0.0;
410  double cost_start = 1.0;
411 
412  // Calculate safety and escape value
413  int length = transformedCloud.points.size();
414  for(int i = 0; i < length; i++)
415  {
416  unsigned int mx, my;
417  double cell_cost;
418  if(mCostmap->worldToMap(transformedCloud.points[i].x, transformedCloud.points[i].y, mx, my))
419  {
420  cell_cost = (double)mCostmap->getCost(mx,my) / costmap_2d::INSCRIBED_INFLATED_OBSTACLE;
421  if(cell_cost >= 1.0)
422  {
423  // Trajectory hit an obstacle
424  break;
425  }
426  }
427  if(i == 0)
428  cost_start = cell_cost;
429  double cost = cell_cost * decay;
430  double safe = (cost_start - cell_cost) * decay * 2.0;
431 
432  if(cost > cost_max) cost_max = cost;
433  if(safe > safe_max) safe_max = safe;
434 
435  decay *= mSafetyDecay;
436  }
437 
438  double action_value = 0.0;
439  double normFactor = 0.0;
440 
441  // Add safety value
442  valueSafety = 1.0 - cost_max;
443  action_value += valueSafety * mSafetyWeight;
444  normFactor += mSafetyWeight;
445 
446  // Add escape value
447  valueEscape = safe_max;
448  action_value += valueEscape * mEscapeWeight;
449  normFactor += mEscapeWeight;
450 
451  if(mRecoverySteps == 0)
452  {
453  // Calculate continuety value
454  valueContinue = (mCurrentDirection - direction) * 0.5;
455  valueContinue = 1.0 - (valueContinue * valueContinue);
456 
457  // Calculate conformance value
458  double corr = (mDesiredDirection - direction) * PI;
459  valueConformance = 0.5 * cos(corr) + 0.5;
460 
461  // Add both to action value
462  action_value += valueConformance * mConformanceWeight;
463  action_value += valueContinue * mContinueWeight;
464  normFactor += mConformanceWeight + mContinueWeight;
465  }
466 
467  action_value /= normFactor;
468 
469  if(debug)
470  {
471  geometry_msgs::Vector3 cost_msg;
472  cost_msg.x = valueSafety;
473  cost_msg.y = valueEscape;
474  cost_msg.z = valueConformance;
475  mCostPublisher.publish(cost_msg);
476  }
477 
478  return action_value;
479 }
480 
481 double diff(double v1, double v2)
482 {
483  if(v1 > v2)
484  return v1 - v2;
485  else
486  return v2 - v1;
487 }
488 
490 {
491  double best_dir = -1.0;
492  double best_value = 0.0;
493  double step = 0.01;
494  double dir = -1.0;
495 
496  while(dir <= 1.0)
497  {
498  double value = evaluateAction(dir, mDesiredVelocity);
499  if(value > best_value)
500  {
501  best_dir = dir;
502  best_value = value;
503  }
504  dir += step;
505  }
506  return best_dir;
507 }
508 
509 sensor_msgs::PointCloud* RobotOperator::getPointCloud(double direction, double velocity)
510 {
511  if(direction < -1) direction = -1;
512  if(direction > 1) direction = 1;
513  int offset = (velocity >= 0) ? LUT_RESOLUTION : 3*LUT_RESOLUTION + 1;
514  int table_index = (direction * LUT_RESOLUTION) + offset;
515  return mTrajTable[table_index];
516 }
d
double mDesiredVelocity
ros::Publisher mPlanPublisher
void executeCommand()
Generates and sends Twist-Message to Robot This is the Operator&#39;s core function and should be called ...
ros::Publisher mCostPublisher
void publish(const boost::shared_ptr< M > &message) const
The core of a ROS node to provide purely reactive obstacle avoidance The RobotOperator is supposed to...
ros::Subscriber mCommandSubscriber
void initTrajTable()
Initializes look-up tables This calculates the trajectories of all possible direction commands...
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
sensor_msgs::PointCloud * getPointCloud(double direction, double velocity)
Get the trajectory defined by the given movement command.
double mMaxVelocity
double evaluateAction(double direction, double velocity, bool debug=false)
Calculate the action value of a given command.
std::string resolve(const std::string &frame_name)
double mDesiredDirection
costmap_2d::Costmap2D * mCostmap
Definition: RobotOperator.h:99
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define CONTROL_TOPIC
Definition: RobotOperator.h:6
ros::Publisher mTrajectoryPublisher
int calculateFreeSpace(sensor_msgs::PointCloud *cloud)
Calculates the distance the robot can move following the given trajectory.
unsigned char getCost(unsigned int mx, unsigned int my) const
void receiveCommand(const nav2d_operator::cmd::ConstPtr &msg)
Callback function to receive move commands.
#define PLAN_TOPIC
Definition: RobotOperator.h:8
double mSafetyDecay
void transformPointCloud(const std::string &target_frame, const sensor_msgs::PointCloud &pcin, sensor_msgs::PointCloud &pcout) const
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
#define LUT_RESOLUTION
Definition: RobotOperator.h:9
#define ROS_WARN_THROTTLE(period,...)
#define ROS_INFO(...)
costmap_2d::Costmap2DROS * mLocalMap
Definition: RobotOperator.h:98
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define PI
#define COMMAND_TOPIC
Definition: RobotOperator.h:5
double mCurrentVelocity
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROUTE_TOPIC
Definition: RobotOperator.h:7
unsigned int step
ros::Publisher mControlPublisher
double diff(double v1, double v2)
static Time now()
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
double mCurrentDirection
std::string mOdometryFrame
double getResolution() const
Costmap2D * getCostmap()
double mMaxFreeSpace
std::string mRobotFrame
double findBestDirection()
Evaluates all possible directions with a fixed resolution.
tf::TransformListener mTfListener
#define ROS_ERROR(...)
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
double mRasterSize
unsigned int mRecoverySteps
#define ROS_DEBUG(...)
sensor_msgs::PointCloud * mTrajTable[(LUT_RESOLUTION *4)+2]


nav2d_operator
Author(s): Sebastian Kasperski
autogenerated on Thu Jun 6 2019 19:20:40