cob_linear_nav.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 //##################
19 //#### includes ####
20 
21 // standard includes
22 //--
23 
24 // ROS includes
25 #include <ros/ros.h>
26 #include <angles/angles.h>
27 
28 #include <pthread.h>
29 
30 // ROS message includes
33 #include <move_base_msgs/MoveBaseAction.h>
34 
35 #include <geometry_msgs/Twist.h>
36 #include <geometry_msgs/PoseStamped.h>
37 #include <nav_msgs/Odometry.h>
38 #include <cob_srvs/SetString.h>
39 
40 #include <tf/transform_listener.h>
41 
42 //####################
43 //#### node class ####
44 class NodeClass
45 {
46  public:
47  // create a handle for this node, initialize node
49 
50  // declaration of topics
52 
54 
56 
57  // declaration of action server
59  move_base_msgs::MoveBaseResult result_; //result is of type geometry_msgs/PoseStamped
60 
61  //declaration of action client to forward move_base_simple messages
63 
64 
65  // Constructor
66  NodeClass(std::string name) :
67  as_(nh_, name, boost::bind(&NodeClass::actionCB, this, _1), false)
68  {
69  m_mutex = PTHREAD_MUTEX_INITIALIZER;
70 
71  ros::NodeHandle private_nh("~");
72 
73  // implementation of topics to publish
74  topic_pub_command_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel", 1);
75 
76  //we'll provide a mechanism for some people to send goals as PoseStamped messages over a topic
77  //they won't get any useful information back about its status, but this is useful for tools
78  //like nav_view and rviz
79  ros::NodeHandle simple_nh("move_base_linear_simple");
80  goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, boost::bind(&NodeClass::topicCB, this, _1));
81 
83 
84  // subscribe to odometry
85  odometry_sub_ = nh_.subscribe<nav_msgs::Odometry>("odom", 1, boost::bind(&NodeClass::odometryCB, this, _1));
86 
87  ss_ = private_nh.advertiseService("set_global_frame", &NodeClass::serviceCB, this);
88 
89  // read parameters from parameter server
90  if(!private_nh.hasParam("kv")) ROS_WARN("Used default parameter for kv [2.5]");
91  private_nh.param("kv", kv_, 2.5);
92 
93  if(!private_nh.hasParam("kp")) ROS_WARN("Used default parameter for kp [3.0]");
94  private_nh.param("kp", kp_, 3.0);
95 
96  if(!private_nh.hasParam("virt_mass")) ROS_WARN("Used default parameter for virt_mass [0.5]");
97  private_nh.param("virt_mass", virt_mass_, 0.5);
98 
99  if(!private_nh.hasParam("vmax")) ROS_WARN("Used default parameter for vmax [0.3 m/s]");
100  private_nh.param("vmax", v_max_, 0.3);
101 
102  if(!private_nh.hasParam("goal_threshold")) ROS_WARN("Used default parameter for goal_threshold [0.03 cm]");
103  private_nh.param("goal_threshold", goal_threshold_, 0.03);
104 
105  if(!private_nh.hasParam("speed_threshold")) ROS_WARN("Used default parameter for speed_threshold [0.08 m/s]");
106  private_nh.param("speed_threshold", speed_threshold_, 0.08);
107 
108  if(!private_nh.hasParam("kv_rot")) ROS_WARN("Used default parameter for kv_rot [2.0]");
109  private_nh.param("kv_rot", kv_rot_, 2.0);
110 
111  if(!private_nh.hasParam("kp_rot")) ROS_WARN("Used default parameter for kp_rot [2.0]");
112  private_nh.param("kp_rot", kp_rot_, 2.0);
113 
114  if(!private_nh.hasParam("virt_mass_rot")) ROS_WARN("Used default parameter for virt_mass_rot [0.5]");
115  private_nh.param("virt_mass_rot", virt_mass_rot_, 0.5);
116 
117  if(!private_nh.hasParam("vtheta_max")) ROS_WARN("Used default parameter for vtheta_max [0.3 rad/s]");
118  private_nh.param("vtheta_max", vtheta_max_, 0.3);
119 
120  if(!private_nh.hasParam("goal_threshold_rot")) ROS_WARN("Used default parameter for goal_threshold_rot [0.08 rad]");
121  private_nh.param("goal_threshold_rot", goal_threshold_rot_, 0.08);
122 
123  if(!private_nh.hasParam("speed_threshold_rot")) ROS_WARN("Used default parameter for speed_threshold_rot [0.08 rad/s]");
124  private_nh.param("speed_threshold_rot", speed_threshold_rot_, 0.08);
125 
126  if(!private_nh.hasParam("goal_abortion_speed")) ROS_WARN("Used default parameter for goal_abortion_speed [0.01 m/s]");
127  private_nh.param("goal_abortion_speed", goal_abortion_speed_, 0.01);
128 
129  if(!private_nh.hasParam("goal_abortion_speed_rot")) ROS_WARN("Used default parameter for goal_abortion_speed_rot [0.01 rad/s]");
130  private_nh.param("goal_abortion_speed_rot", goal_abortion_speed_rot_, 0.01);
131 
132  if(!private_nh.hasParam("global_frame")) ROS_WARN("Used default parameter for global_frame [/map]");
133  private_nh.param("global_frame", global_frame_, std::string("map"));
134 
135  if(!private_nh.hasParam("robot_frame")) ROS_WARN("Used default parameter for robot_frame [/base_link]");
136  private_nh.param("robot_frame", robot_frame_, std::string("base_link"));
137 
138  if(!private_nh.hasParam("robot_footprint_frame")) ROS_WARN("Used default parameter for robot_footprint_frame [/base_footprint]");
139  private_nh.param("robot_footprint_frame", robot_footprint_frame_, std::string("base_footprint"));
140 
141  if(!private_nh.hasParam("slow_down_distance")) ROS_WARN("Used default parameter for slow_down_distance [0.5m]");
142  private_nh.param("slow_down_distance", slow_down_distance_, 0.5);
143 
144  if(!private_nh.hasParam("goal_abortion_time")) ROS_WARN("Used default parameter for goal_abortion_time [5.0s]");
145  private_nh.param("goal_abortion_time", goal_abortion_time_, 5.0);
146 
147  if(!private_nh.hasParam("use_move_action")) ROS_WARN("Used default parameter for use_move_action [true]");
148  private_nh.param("use_move_action", use_move_action_, true);
149 
150  //generate robot zero_pose
151  zero_pose_.pose.position.x = 0.0;
152  zero_pose_.pose.position.y = 0.0;
153  zero_pose_.pose.position.z = 0.0;
154  zero_pose_.pose.orientation.x = 0.0;
155  zero_pose_.pose.orientation.y = 0.0;
156  zero_pose_.pose.orientation.z = 0.0;
157  zero_pose_.pose.orientation.w = 1.0;
158  zero_pose_.header.frame_id = robot_frame_;
159  zero_pose_.header.stamp = ros::Time::now();
161  robot_pose_global_.header.frame_id = global_frame_;
163  // at startup, the robot is should not move
164  move_ = false;
165 
166  // also initialize variables that are used later on!
168  vtheta_last_ = 0.0;
169 
170  //start action server, it holds the main loop while driving
171  as_.start();
172  }
173 
174  void topicCB(const geometry_msgs::PoseStamped::ConstPtr& goal)
175  {
176 
177  if(!goalValid(*goal))
178  return;
179 
180  if(use_move_action_)
181  {
182  ROS_INFO("In ROS goal callback, wrapping the PoseStamped in the action message and re-sending to the server.");
183  move_base_msgs::MoveBaseGoal action_goal;
184 
185  action_goal.target_pose = transformGoalToMap(*goal);
186 
187  action_client_->sendGoal(action_goal);
188  action_client_->stopTrackingGoal();
189  }
190  else
191  {
192  ROS_DEBUG("In ROS goal callback, using the PoseStamped as error and start control step.");
193 
195 
197 
198  if(last_time_ < 0)
199  {
200  vtheta_last_ = 0.0f;
201  vx_last_ = 0.0f;
202  vy_last_ = 0.0f;
204  }
205 
206  x_last_ = robot_pose_global_.pose.position.x;
207  y_last_ = robot_pose_global_.pose.position.y;
208  theta_last_ = tf::getYaw(robot_pose_global_.pose.orientation);
209 
211 
212  move_ = true;
213 
214  }
215 
216  }
217 
218  void actionCB(const move_base_msgs::MoveBaseGoalConstPtr &goal)
219  {
220  if(!goalValid(goal->target_pose))
221  {
222  as_.setAborted(move_base_msgs::MoveBaseResult(), "Aborting because a transformation could not be found");
223  return;
224  }
225  // goal is of type geometry_msgs/PoseStamped
226  ROS_INFO("In idle mode, new goal accepted");
227 
229 
231  x_last_ = robot_pose_global_.pose.position.x;
232  y_last_ = robot_pose_global_.pose.position.y;
233  theta_last_ = tf::getYaw(robot_pose_global_.pose.orientation);
234  vtheta_last_ = 0.0f;
235  vx_last_ = 0.0f;
236  vy_last_ = 0.0f;
238 
239  goal_pose_global_ = transformGoalToMap(goal->target_pose);
240 
241  move_ = true;
242 
243  ros::Rate loop_rate(100);
244  while(nh_.ok()) {
245  loop_rate.sleep();
246 
247  if(as_.isPreemptRequested()) {
248  if(as_.isNewGoalAvailable()) {
249  ROS_INFO("New goal received, updating movement");
250  //if we're active and a new goal is available, we'll accept it
251  move_base_msgs::MoveBaseGoal new_goal = * as_.acceptNewGoal();
252  goal_pose_global_ = transformGoalToMap(new_goal.target_pose);
253 
255  move_ = true;
256  } else {
257  ROS_INFO("Preempt requested, aborting movement");
258  //notify the ActionServer that we've successfully preempted
259  as_.setPreempted();
260 
261  move_ = false;
262  stopMovement();
263  return;
264  }
265  }
266 
268 
269  if(finished_) {
270  as_.setSucceeded(move_base_msgs::MoveBaseResult(), "Goal reached.");
271  ROS_INFO("Goal reached.");
272  return;
273  }
274 
275  if(!as_.isActive()) {
276  ROS_INFO("Goal not active anymore. Stop!");
277  return;
278  }
279  }
280 
281 
282  //if the node is killed then we'll abort and return
283  stopMovement();
284  as_.setAborted(move_base_msgs::MoveBaseResult(), "Aborting on the goal because the node has been killed");
285  return;
286  };
287 
288 
289  void odometryCB(const nav_msgs::Odometry::ConstPtr &odometry){
290  geometry_msgs::Vector3Stamped vec_stamped;
291 
292  vec_stamped.vector = odometry->twist.twist.linear;
293  vec_stamped.header.frame_id = robot_footprint_frame_;
294  try
295  {
296  tf_listener_.waitForTransform(robot_frame_, vec_stamped.header.frame_id, ros::Time(0), ros::Duration(1.0));
298  }
299  catch(tf::TransformException& ex){ROS_ERROR("%s",ex.what());}
300 
301  vec_stamped.vector = odometry->twist.twist.angular;
302  vec_stamped.header.frame_id = robot_footprint_frame_;
303  try
304  {
305  tf_listener_.waitForTransform(robot_frame_, vec_stamped.header.frame_id, ros::Time(0), ros::Duration(1.0));
307  }
308  catch(tf::TransformException& ex){ROS_ERROR("%s",ex.what());}
309  }
310 
311  bool serviceCB(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
312  {
313  global_frame_ = req.data;
314  ros::NodeHandle private_nh("~");
315  private_nh.setParam("global_frame", req.data);
316  ROS_INFO_STREAM("Set global frame to: " << req.data);
317  res.success = true;
318  res.message = "";
319 
320  return true;
321  }
322 
323  // Destructor
325  {
326  }
327 
328  void performControllerStep();
329  bool getUseMoveAction(void);
330 
331 private:
334  geometry_msgs::PoseStamped goal_pose_global_;
335  geometry_msgs::PoseStamped zero_pose_;
336  geometry_msgs::PoseStamped robot_pose_global_;
338 
340 
342 
344 
345  pthread_mutex_t m_mutex;
346 
347  //core functions:
348  void publishVelocitiesGlobal(double vx, double vy, double theta);
349  geometry_msgs::PoseStamped transformGoalToMap(geometry_msgs::PoseStamped goal_pose);
350  geometry_msgs::PoseStamped getRobotPoseGlobal();
351 
352  //helper functions:
353  double getDistance2d(geometry_msgs::PoseStamped a, geometry_msgs::PoseStamped b);
354  double getDistance2d(geometry_msgs::Point a, geometry_msgs::Point b);
355  double getThetaDiffRad(double target, double actual);
356  double sign(double x);
357  void stopMovement();
358  bool notMovingDueToObstacle();
359  bool goalValid(const geometry_msgs::PoseStamped& goal_pose);
360 
361  //Potential field Controller variables
365  double kp_, kv_, virt_mass_;
367  double last_time_;
370 
371 }; //NodeClass
372 
374 {
375  return use_move_action_;
376 }
377 
378 geometry_msgs::PoseStamped NodeClass::transformGoalToMap(geometry_msgs::PoseStamped goal_pose) {
379  geometry_msgs::PoseStamped goal_global_;
380  if(goal_pose.header.frame_id == global_frame_) return goal_pose;
381  else if(tf_listener_.canTransform(global_frame_, goal_pose.header.frame_id, ros::Time(0), new std::string)) {
382  tf_listener_.transformPose(global_frame_, ros::Time(0), goal_pose, "base_link", goal_global_);
383  return goal_global_;
384  } else {
385  ROS_WARN("Can't transform goal to global frame %s", global_frame_.c_str());
386  return robot_pose_global_;
387  }
388 }
389 
390 geometry_msgs::PoseStamped NodeClass::getRobotPoseGlobal() {
391  try
392  {
393  ros::Time now = ros::Time::now();
396  }
397  catch(tf::TransformException& ex){
398  ROS_WARN("Failed to find robot pose in global frame %s", global_frame_.c_str());
400  return zero_pose_;
401  }
402 
403  return robot_pose_global_;
404 }
405 
406 double NodeClass::getDistance2d(geometry_msgs::PoseStamped a, geometry_msgs::PoseStamped b) {
407  return sqrt( pow(a.pose.position.x - b.pose.position.x,2) + pow(a.pose.position.y - b.pose.position.y,2) );
408 }
409 
410 double NodeClass::getDistance2d(geometry_msgs::Point a, geometry_msgs::Point b) {
411  return sqrt( pow(a.x - b.x,2) + pow(a.y - b.y,2) );
412 }
413 
414 double NodeClass::sign(double x) {
415  if(x >= 0.0f) return 1.0f;
416  else return -1.0f;
417 }
418 
419 double NodeClass::getThetaDiffRad(double target, double actual) {
420  return angles::shortest_angular_distance(actual, target);
421 }
422 
423 void NodeClass::publishVelocitiesGlobal(double vx, double vy, double theta) {
424  //Transform commands from global frame to robot coordinate system
425  geometry_msgs::Vector3Stamped cmd_global, cmd_robot;
426  geometry_msgs::Twist msg;
427 
428  cmd_global.header.frame_id = global_frame_;
429  cmd_global.header.stamp = ros::Time::now();
430  cmd_global.vector.x = vx;
431  cmd_global.vector.y = vy;
432  try
433  {
434  tf_listener_.waitForTransform(robot_frame_, cmd_global.header.frame_id, cmd_global.header.stamp, ros::Duration(1.0));
435  tf_listener_.transformVector(robot_frame_, cmd_global, cmd_robot);
436  } catch (tf::TransformException ex){
437  ROS_ERROR("%s",ex.what());
438  cmd_robot.vector.x = 0.0f;
439  cmd_robot.vector.y = 0.0f;
440  }
441 
442  // make sure that the published velocities are in an at least somewhat reasonable range
443  try
444  {
445  if ( std::isnan(cmd_robot.vector.x) || std::isnan(cmd_robot.vector.y) || std::isnan(theta) )
446  {
447  std::string err = "linear_nav: Output velocity contains NaN!";
448  throw err;
449  }
450  if ( ! ( fabs(cmd_robot.vector.x) < 5.0 && fabs(cmd_robot.vector.y) < 5.0 && fabs(theta) < M_PI ) )
451  {
452  std::string err = "linear_nav: Output velocity too high (x="+std::to_string(cmd_robot.vector.x)+" y="+std::to_string(cmd_robot.vector.y)+" theta="+std::to_string(theta)+")";
453  throw err;
454  }
455  }
456  catch ( std::string err )
457  {
458  ROS_ERROR("%s", err.c_str());
459  topic_pub_command_.publish(geometry_msgs::Twist());
460  return;
461  }
462 
463 
464  msg.linear = cmd_robot.vector;
465  msg.angular.z = theta;
466  msg.linear.z = 0.0; msg.angular.x = 0.0; msg.angular.y = 0.0;
467 
469 }
470 
472  publishVelocitiesGlobal(0.0f, 0.0f, 0.0f);
473  vx_last_ = 0.0f;
474  vy_last_ = 0.0f;
475  vtheta_last_ = 0.0f;
476 }
477 
479  if (move_ == true && // should move
480  finished_ == false && // has not reached goal
481  fabs(robot_twist_linear_robot_.vector.x) <= goal_abortion_speed_ && // velocity components are small
484  ros::Time::now().toSec() - last_time_moving_ > goal_abortion_time_ ) // has not been moving for x seconds
485  {
486  return true;
487  } else if ( fabs(robot_twist_linear_robot_.vector.x) > goal_abortion_speed_ ||
490  { // still moving, then update last_time_moving_
492  }
493 
494  return false;
495 }
496 
497 bool NodeClass::goalValid(const geometry_msgs::PoseStamped& goal_pose)
498 {
499  if( goal_pose.pose.orientation.x == 0.0 &&
500  goal_pose.pose.orientation.y == 0.0 &&
501  goal_pose.pose.orientation.z == 0.0 &&
502  goal_pose.pose.orientation.w == 0.0 )
503  {
504  ROS_WARN("Goal invalid! Received Quaternion with all values 0.0!");
505  return false;
506  }
507  else if (!tf_listener_.waitForTransform(global_frame_, goal_pose.header.frame_id, goal_pose.header.stamp, ros::Duration(1.0)))
508  {
509  ROS_WARN_STREAM("Can not transform goal which is given in /"
510  << goal_pose.header.frame_id << " into global frame /" << global_frame_);
511  return false;
512  }
513  else if (!tf_listener_.waitForTransform(robot_frame_, goal_pose.header.frame_id, goal_pose.header.stamp, ros::Duration(1.0)))
514  {
515  ROS_WARN_STREAM("Can not transform goal which is given in /"
516  << goal_pose.header.frame_id << " into robot frame /" << robot_frame_);
517  return false;
518  }
519  else
520  {
521  return true;
522  }
523 }
524 
526  pthread_mutex_lock(&m_mutex);
527  ROS_DEBUG_STREAM_NAMED("mutex", "performControllerStep: locked mutex");
528 
529  double dt;
530  double F_x, F_y, F_theta;
531  double distance_to_goal;
532  double theta, theta_goal;
533  double cmd_vx, cmd_vy, cmd_vtheta;
534  double vx_d, vy_d, vtheta_d, v_factor;
535  double v_max_goal = v_max_;
536 
537  if(!move_) {
538  if(!use_move_action_)
540  pthread_mutex_unlock(&m_mutex);
541  ROS_DEBUG_STREAM_NAMED("mutex", "performControllerStep: released mutex");
542  return;
543  }
544 
546 
548  theta = tf::getYaw(robot_pose_global_.pose.orientation);
549  theta_goal = tf::getYaw(goal_pose_global_.pose.orientation);
550 
551  //exit, if positions and velocities lie inside thresholds
552  if( distance_to_goal <= goal_threshold_ &&
554  fabs(getThetaDiffRad(theta_goal, theta)) <= goal_threshold_rot_ &&
556  {
557  finished_ = true;
558  move_ = false;
559  stopMovement();
560  if(!use_move_action_)
562  pthread_mutex_unlock(&m_mutex);
563  ROS_DEBUG_STREAM_NAMED("mutex", "performControllerStep: released mutex");
564  return;
565  } else if( notMovingDueToObstacle() == true ) {
566  finished_ = false;
567  move_ = false;
568  stopMovement();
569  if(use_move_action_)
570  {
571  as_.setAborted(move_base_msgs::MoveBaseResult(), "Cancel the goal because an obstacle is blocking the path.");
572  }
573  else
574  {
576  }
577  ROS_INFO("Cancel the goal because an obstacle is blocking the path.");
578  pthread_mutex_unlock(&m_mutex);
579  ROS_DEBUG_STREAM_NAMED("mutex", "performControllerStep: released mutex");
580  return;
581  } else finished_ = false;
582 
583  dt = ros::Time::now().toSec() - last_time_;
585 
586  //Slow down while approaching goal
587  if(distance_to_goal < slow_down_distance_) {
588  //implementation for linear decrease of v_max:
589  double goal_linear_slope = v_max_ / slow_down_distance_;
590  v_max_goal = distance_to_goal * goal_linear_slope;
591 
592  if(v_max_goal > v_max_) v_max_goal = v_max_;
593  else if(v_max_goal < 0.0f) v_max_goal = 0.0f;
594  }
595 
596  //Translational movement
597  //calculation of v factor to limit maxspeed
598  vx_d = kp_/kv_ * (goal_pose_global_.pose.position.x - robot_pose_global_.pose.position.x);
599  vy_d = kp_/kv_ * (goal_pose_global_.pose.position.y - robot_pose_global_.pose.position.y);
600  v_factor = v_max_goal / sqrt(vy_d*vy_d + vx_d*vx_d);
601 
602  if(v_factor > 1.0) v_factor = 1.0;
603 
604  F_x = - kv_ * vx_last_ + v_factor * kp_ * (goal_pose_global_.pose.position.x - robot_pose_global_.pose.position.x);
605  F_y = - kv_ * vy_last_ + v_factor * kp_ * (goal_pose_global_.pose.position.y - robot_pose_global_.pose.position.y);
606 
607  cmd_vx = vx_last_ + F_x / virt_mass_ * dt;
608  cmd_vy = vy_last_ + F_y / virt_mass_ * dt;
609 
610  //Rotational Movement
611  //calculation of v factor to limit maxspeed
612  vtheta_d = kp_rot_ / kv_rot_ * getThetaDiffRad(theta_goal, theta);
613  v_factor = fabs(vtheta_max_ / vtheta_d);
614  if(v_factor > 1.0) v_factor = 1.0;
615 
616  F_theta = - kv_rot_ * vtheta_last_ + v_factor * kp_rot_ * getThetaDiffRad(theta_goal, theta);
617  cmd_vtheta = vtheta_last_ + F_theta / virt_mass_rot_ * dt;
618 
619  //Publish velocities, these calculated forces and velocities are for the global frame
620  //they are transformed to robot_frame later
621  x_last_ = robot_pose_global_.pose.position.x;
622  y_last_ = robot_pose_global_.pose.position.y;
623  theta_last_ = theta;
624  vx_last_ = cmd_vx;
625  vy_last_ = cmd_vy;
626  vtheta_last_ = cmd_vtheta;
627 
628  publishVelocitiesGlobal(cmd_vx, cmd_vy, cmd_vtheta);
629  pthread_mutex_unlock(&m_mutex);
630  ROS_DEBUG_STREAM_NAMED("mutex", "performControllerStep: released mutex");
631 }
632 
633 
634 
635 //#######################
636 //#### main programm ####
637 int main(int argc, char** argv)
638 {
639  // initialize ROS, spezify name of node
640  ros::init(argc, argv, "cob_linear");
641 
642  // create nodeClass
643  NodeClass nodeClass("move_base_linear");
644 
645  if(nodeClass.getUseMoveAction())
646  {
647  ros::spin();
648  }
649  else
650  {
651  ros::Rate loop_rate(100);
652  while(nodeClass.nh_.ok())
653  {
654  nodeClass.performControllerStep();
655  loop_rate.sleep();
656  ros::spinOnce();
657  }
658  }
659 
660  return 0;
661 }
662 
geometry_msgs::PoseStamped transformGoalToMap(geometry_msgs::PoseStamped goal_pose)
double speed_threshold_
void stopMovement()
bool goalValid(const geometry_msgs::PoseStamped &goal_pose)
boost::shared_ptr< const Goal > acceptNewGoal()
double theta_last_
pthread_mutex_t m_mutex
double goal_abortion_speed_rot_
geometry_msgs::Vector3Stamped robot_twist_angular_robot_
#define ROS_DEBUG_STREAM_NAMED(name, args)
void publish(const boost::shared_ptr< M > &message) const
double getThetaDiffRad(double target, double actual)
f
std::string robot_frame_
double goal_threshold_
double slow_down_distance_
void actionCB(const move_base_msgs::MoveBaseGoalConstPtr &goal)
static double getYaw(const Quaternion &bt_q)
bool getUseMoveAction(void)
void topicCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::NodeHandle nh_
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > * action_client_
geometry_msgs::Vector3Stamped robot_twist_linear_robot_
geometry_msgs::PoseStamped getRobotPoseGlobal()
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > as_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::Subscriber goal_sub_
#define ROS_WARN(...)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
double getDistance2d(geometry_msgs::PoseStamped a, geometry_msgs::PoseStamped b)
ROSCPP_DECL void spin(Spinner &spinner)
std::string robot_footprint_frame_
double virt_mass_rot_
double vtheta_max_
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
double goal_abortion_time_
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
double virt_mass_
double sign(double x)
geometry_msgs::PoseStamped zero_pose_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double vtheta_last_
#define ROS_WARN_STREAM(args)
void publishVelocitiesGlobal(double vx, double vy, double theta)
bool sleep()
ros::ServiceServer ss_
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
double last_time_
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
move_base_msgs::MoveBaseResult result_
#define ROS_INFO_STREAM(args)
geometry_msgs::PoseStamped goal_pose_global_
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
bool notMovingDueToObstacle()
void performControllerStep()
static Time now()
bool use_move_action_
double goal_abortion_speed_
bool serviceCB(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
bool ok() const
tf::TransformListener tf_listener_
bool hasParam(const std::string &key) const
int main(int argc, char **argv)
ros::Subscriber odometry_sub_
ROSCPP_DECL void spinOnce()
void transformVector(const std::string &target_frame, const geometry_msgs::Vector3Stamped &stamped_in, geometry_msgs::Vector3Stamped &stamped_out) const
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
ros::Publisher topic_pub_command_
double last_time_moving_
NodeClass(std::string name)
double speed_threshold_rot_
def shortest_angular_distance(from_angle, to_angle)
void odometryCB(const nav_msgs::Odometry::ConstPtr &odometry)
geometry_msgs::PoseStamped robot_pose_global_
double goal_threshold_rot_
#define ROS_DEBUG(...)
std::string global_frame_


cob_linear_nav
Author(s): Matthias Gruhler , Philipp Koehler
autogenerated on Sat Oct 24 2020 03:50:45