00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061 #include <ros/ros.h>
00062 #include <XmlRpc.h>
00063
00064 #include <pthread.h>
00065
00066
00067 #include <actionlib/client/simple_action_client.h>
00068 #include <actionlib/server/simple_action_server.h>
00069 #include <move_base_msgs/MoveBaseAction.h>
00070
00071 #include <geometry_msgs/Twist.h>
00072 #include <geometry_msgs/PoseStamped.h>
00073 #include <nav_msgs/Odometry.h>
00074
00075 #include <tf/transform_listener.h>
00076
00077
00078
00079 class NodeClass
00080 {
00081 public:
00082
00083 ros::NodeHandle nh_;
00084
00085
00086 ros::Publisher topic_pub_command_;
00087
00088 ros::Subscriber goal_sub_, odometry_sub_;
00089
00090
00091 actionlib::SimpleActionServer<move_base_msgs::MoveBaseAction> as_;
00092 move_base_msgs::MoveBaseResult result_;
00093
00094
00095 actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> * action_client_;
00096
00097
00098
00099 NodeClass(std::string name) :
00100 as_(nh_, name, boost::bind(&NodeClass::actionCB, this, _1), false)
00101 {
00102 m_mutex = PTHREAD_MUTEX_INITIALIZER;
00103
00104 ros::NodeHandle private_nh("~");
00105
00106
00107 topic_pub_command_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00108
00109
00110
00111
00112 ros::NodeHandle simple_nh("move_base_linear_simple");
00113 goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, boost::bind(&NodeClass::topicCB, this, _1));
00114
00115 action_client_ = new actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>(nh_, name);
00116
00117
00118 odometry_sub_ = nh_.subscribe<nav_msgs::Odometry>("odom", 1, boost::bind(&NodeClass::odometryCB, this, _1));
00119
00120
00121 if(!private_nh.hasParam("kv")) ROS_WARN("Used default parameter for kv [2.5]");
00122 private_nh.param("kv", kv_, 2.5);
00123
00124 if(!private_nh.hasParam("kp")) ROS_WARN("Used default parameter for kp [3.0]");
00125 private_nh.param("kp", kp_, 3.0);
00126
00127 if(!private_nh.hasParam("virt_mass")) ROS_WARN("Used default parameter for virt_mass [0.5]");
00128 private_nh.param("virt_mass", virt_mass_, 0.5);
00129
00130 if(!private_nh.hasParam("vmax")) ROS_WARN("Used default parameter for vmax [0.3 m/s]");
00131 private_nh.param("vmax", v_max_, 0.3);
00132
00133 if(!private_nh.hasParam("goal_threshold")) ROS_WARN("Used default parameter for goal_threshold [0.03 cm]");
00134 private_nh.param("goal_threshold", goal_threshold_, 0.03);
00135
00136 if(!private_nh.hasParam("speed_threshold")) ROS_WARN("Used default parameter for speed_threshold [0.08 m/s]");
00137 private_nh.param("speed_threshold", speed_threshold_, 0.08);
00138
00139 if(!private_nh.hasParam("kv_rot")) ROS_WARN("Used default parameter for kv_rot [2.0]");
00140 private_nh.param("kv_rot", kv_rot_, 2.0);
00141
00142 if(!private_nh.hasParam("kp_rot")) ROS_WARN("Used default parameter for kp_rot [2.0]");
00143 private_nh.param("kp_rot", kp_rot_, 2.0);
00144
00145 if(!private_nh.hasParam("virt_mass_rot")) ROS_WARN("Used default parameter for virt_mass_rot [0.5]");
00146 private_nh.param("virt_mass_rot", virt_mass_rot_, 0.5);
00147
00148 if(!private_nh.hasParam("vtheta_max")) ROS_WARN("Used default parameter for vtheta_max [0.3 rad/s]");
00149 private_nh.param("vtheta_max", vtheta_max_, 0.3);
00150
00151 if(!private_nh.hasParam("goal_threshold_rot")) ROS_WARN("Used default parameter for goal_threshold_rot [0.08 rad]");
00152 private_nh.param("goal_threshold_rot", goal_threshold_rot_, 0.08);
00153
00154 if(!private_nh.hasParam("speed_threshold_rot")) ROS_WARN("Used default parameter for speed_threshold_rot [0.08 rad/s]");
00155 private_nh.param("speed_threshold_rot", speed_threshold_rot_, 0.08);
00156
00157 if(!private_nh.hasParam("global_frame")) ROS_WARN("Used default parameter for global_frame [/map]");
00158 private_nh.param("global_frame", global_frame_, std::string("map"));
00159
00160 if(!private_nh.hasParam("robot_frame")) ROS_WARN("Used default parameter for robot_frame [/base_link]");
00161 private_nh.param("robot_frame", robot_frame_, std::string("base_link"));
00162
00163 if(!private_nh.hasParam("slow_down_distance")) ROS_WARN("Used default parameter for slow_down_distance [0.5m]");
00164 private_nh.param("slow_down_distance", slow_down_distance_, 0.5);
00165
00166 if(!private_nh.hasParam("goal_abortion_time")) ROS_WARN("Used default parameter for goal_abortion_time [5.0s]");
00167 private_nh.param("goal_abortion_time", goal_abortion_time_, 5.0);
00168
00169 if(!private_nh.hasParam("use_move_action")) ROS_WARN("Used default parameter for use_move_action [true]");
00170 private_nh.param("use_move_action", use_move_action_, true);
00171
00172
00173 zero_pose_.pose.position.x = 0.0;
00174 zero_pose_.pose.position.y = 0.0;
00175 zero_pose_.pose.position.z = 0.0;
00176 zero_pose_.pose.orientation.x = 0.0;
00177 zero_pose_.pose.orientation.y = 0.0;
00178 zero_pose_.pose.orientation.z = 0.0;
00179 zero_pose_.pose.orientation.w = 1.0;
00180 zero_pose_.header.frame_id = robot_frame_;
00181 zero_pose_.header.stamp = ros::Time::now();
00182 robot_pose_global_ = zero_pose_;
00183 robot_pose_global_.header.frame_id = global_frame_;
00184 goal_pose_global_ = robot_pose_global_;
00185
00186 move_ = false;
00187
00188
00189 last_time_ = ros::Time::now().toSec();
00190 vtheta_last_ = 0.0;
00191
00192
00193 ros::Time last_error = ros::Time::now();
00194 std::string tf_error;
00195 while(!tf_listener_.waitForTransform(global_frame_, robot_frame_, ros::Time(), ros::Duration(0.1), ros::Duration(0.01), &tf_error)) {
00196 ros::spinOnce();
00197 if(last_error + ros::Duration(5.0) < ros::Time::now()){
00198 ROS_WARN("Waiting on transform from %s to %s to become available before running cob_linear_nav, tf error: %s",
00199 robot_frame_.c_str(), global_frame_.c_str(), tf_error.c_str());
00200 last_error = ros::Time::now();
00201 }
00202 }
00203
00204
00205 as_.start();
00206 }
00207
00208 void topicCB(const geometry_msgs::PoseStamped::ConstPtr& goal)
00209 {
00210
00211 if(!goalValid(goal->pose))
00212 return;
00213
00214 if(use_move_action_)
00215 {
00216 ROS_INFO("In ROS goal callback, wrapping the PoseStamped in the action message and re-sending to the server.");
00217 move_base_msgs::MoveBaseGoal action_goal;
00218
00219 action_goal.target_pose = transformGoalToMap(*goal);
00220
00221 action_client_->sendGoal(action_goal);
00222 action_client_->stopTrackingGoal();
00223 }
00224 else
00225 {
00226 ROS_DEBUG("In ROS goal callback, using the PoseStamped as error and start control step.");
00227
00228 last_time_moving_ = ros::Time::now().toSec();
00229
00230 getRobotPoseGlobal();
00231
00232 if(last_time_ < 0)
00233 {
00234 vtheta_last_ = 0.0f;
00235 vx_last_ = 0.0f;
00236 vy_last_ = 0.0f;
00237 last_time_ = ros::Time::now().toSec();
00238 }
00239
00240 x_last_ = robot_pose_global_.pose.position.x;
00241 y_last_ = robot_pose_global_.pose.position.y;
00242 theta_last_ = tf::getYaw(robot_pose_global_.pose.orientation);
00243
00244 goal_pose_global_ = transformGoalToMap(*goal);
00245
00246 move_ = true;
00247
00248 }
00249
00250 }
00251
00252 void actionCB(const move_base_msgs::MoveBaseGoalConstPtr &goal)
00253 {
00254 if(!goalValid(goal->target_pose.pose))
00255 return;
00256
00257 ROS_INFO("In idle mode, new goal accepted");
00258
00259 last_time_moving_ = ros::Time::now().toSec();
00260
00261 getRobotPoseGlobal();
00262 x_last_ = robot_pose_global_.pose.position.x;
00263 y_last_ = robot_pose_global_.pose.position.y;
00264 theta_last_ = tf::getYaw(robot_pose_global_.pose.orientation);
00265 vtheta_last_ = 0.0f;
00266 vx_last_ = 0.0f;
00267 vy_last_ = 0.0f;
00268 last_time_ = ros::Time::now().toSec();
00269
00270 goal_pose_global_ = transformGoalToMap(goal->target_pose);
00271
00272 move_ = true;
00273
00274 ros::Rate loop_rate(100);
00275 while(nh_.ok()) {
00276 loop_rate.sleep();
00277
00278 if(as_.isPreemptRequested()) {
00279 if(as_.isNewGoalAvailable()) {
00280 ROS_INFO("New goal received, updating movement");
00281
00282 move_base_msgs::MoveBaseGoal new_goal = * as_.acceptNewGoal();
00283 goal_pose_global_ = transformGoalToMap(new_goal.target_pose);
00284
00285 last_time_moving_ = ros::Time::now().toSec();
00286 move_ = true;
00287 } else {
00288 ROS_INFO("Preempt requested, aborting movement");
00289
00290 as_.setPreempted();
00291
00292 move_ = false;
00293 stopMovement();
00294 return;
00295 }
00296 }
00297
00298 performControllerStep();
00299
00300 if(finished_) {
00301 as_.setSucceeded(move_base_msgs::MoveBaseResult(), "Goal reached.");
00302 ROS_INFO("Goal reached.");
00303 return;
00304 }
00305
00306 if(!as_.isActive()) {
00307 ROS_INFO("Goal not active anymore. Stop!");
00308 return;
00309 }
00310 }
00311
00312
00313
00314 stopMovement();
00315 as_.setAborted(move_base_msgs::MoveBaseResult(), "Aborting on the goal because the node has been killed");
00316 return;
00317 };
00318
00319
00320 void odometryCB(const nav_msgs::Odometry::ConstPtr &odometry){
00321 geometry_msgs::Vector3Stamped vec_stamped;
00322
00323 vec_stamped.vector = odometry->twist.twist.linear;
00324 vec_stamped.header.frame_id = "base_footprint";
00325 tf_listener_.transformVector(robot_frame_, vec_stamped, robot_twist_linear_robot_);
00326
00327 vec_stamped.vector = odometry->twist.twist.angular;
00328 vec_stamped.header.frame_id = "base_footprint";
00329 tf_listener_.transformVector(robot_frame_, vec_stamped, robot_twist_angular_robot_);
00330 }
00331
00332
00333 ~NodeClass()
00334 {
00335 }
00336
00337 void performControllerStep();
00338 bool getUseMoveAction(void);
00339
00340 private:
00341 tf::TransformListener tf_listener_;
00342 std::string global_frame_, robot_frame_;
00343 geometry_msgs::PoseStamped goal_pose_global_;
00344 geometry_msgs::PoseStamped zero_pose_;
00345 geometry_msgs::PoseStamped robot_pose_global_;
00346 geometry_msgs::Vector3Stamped robot_twist_linear_robot_, robot_twist_angular_robot_;
00347
00348 double slow_down_distance_, goal_abortion_time_;
00349
00350 bool finished_, move_;
00351
00352 bool use_move_action_;
00353
00354 pthread_mutex_t m_mutex;
00355
00356
00357 void publishVelocitiesGlobal(double vx, double vy, double theta);
00358 geometry_msgs::PoseStamped transformGoalToMap(geometry_msgs::PoseStamped goal_pose);
00359 geometry_msgs::PoseStamped getRobotPoseGlobal();
00360
00361
00362 double getDistance2d(geometry_msgs::PoseStamped a, geometry_msgs::PoseStamped b);
00363 double getDistance2d(geometry_msgs::Point a, geometry_msgs::Point b);
00364 double getThetaDiffRad(double target, double actual);
00365 double sign(double x);
00366 void stopMovement();
00367 bool notMovingDueToObstacle();
00368 bool goalValid(const geometry_msgs::Pose & goal);
00369
00370
00371 double vx_last_, vy_last_, x_last_, y_last_, theta_last_, vtheta_last_;
00372 double goal_threshold_, speed_threshold_;
00373 double goal_threshold_rot_, speed_threshold_rot_;
00374 double kp_, kv_, virt_mass_;
00375 double kp_rot_, kv_rot_, virt_mass_rot_;
00376 double last_time_;
00377 double v_max_, vtheta_max_;
00378 double last_time_moving_;
00379
00380 };
00381
00382 bool NodeClass::getUseMoveAction(void)
00383 {
00384 return use_move_action_;
00385 }
00386
00387 geometry_msgs::PoseStamped NodeClass::transformGoalToMap(geometry_msgs::PoseStamped goal_pose) {
00388 geometry_msgs::PoseStamped goal_global_;
00389 if(goal_pose.header.frame_id == global_frame_) return goal_pose;
00390 else if(tf_listener_.canTransform(global_frame_, goal_pose.header.frame_id, ros::Time(0), new std::string)) {
00391 tf_listener_.transformPose(global_frame_, ros::Time(0), goal_pose, "base_link", goal_global_);
00392 return goal_global_;
00393 } else {
00394 ROS_WARN("Can't transform goal to global frame %s", global_frame_.c_str());
00395 return robot_pose_global_;
00396 }
00397 }
00398
00399 geometry_msgs::PoseStamped NodeClass::getRobotPoseGlobal() {
00400 try{
00401 tf_listener_.waitForTransform(global_frame_, robot_frame_, ros::Time(0), ros::Duration(5.0));
00402 tf_listener_.transformPose(global_frame_, ros::Time(0), zero_pose_, robot_frame_, robot_pose_global_);
00403 }
00404 catch(tf::TransformException& ex){
00405 ROS_WARN("Failed to find robot pose in global frame %s", global_frame_.c_str());
00406 robot_pose_global_ = zero_pose_;
00407 return zero_pose_;
00408 }
00409
00410 return robot_pose_global_;
00411 }
00412
00413 double NodeClass::getDistance2d(geometry_msgs::PoseStamped a, geometry_msgs::PoseStamped b) {
00414 return sqrt( pow(a.pose.position.x - b.pose.position.x,2) + pow(a.pose.position.y - b.pose.position.y,2) );
00415 }
00416
00417 double NodeClass::getDistance2d(geometry_msgs::Point a, geometry_msgs::Point b) {
00418 return sqrt( pow(a.x - b.x,2) + pow(a.y - b.y,2) );
00419 }
00420
00421 double NodeClass::sign(double x) {
00422 if(x >= 0.0f) return 1.0f;
00423 else return -1.0f;
00424 }
00425
00426 double NodeClass::getThetaDiffRad(double target, double actual) {
00427 if(fabs(target - actual) <= M_PI) return (target - actual);
00428 else return sign(target - actual) * -2.0f * M_PI - (target - actual);
00429 }
00430
00431 void NodeClass::publishVelocitiesGlobal(double vx, double vy, double theta) {
00432
00433 geometry_msgs::Vector3Stamped cmd_global, cmd_robot;
00434 geometry_msgs::Twist msg;
00435
00436 cmd_global.header.frame_id = global_frame_;
00437 cmd_global.vector.x = vx;
00438 cmd_global.vector.y = vy;
00439 try { tf_listener_.transformVector(robot_frame_, cmd_global, cmd_robot);
00440 } catch (tf::TransformException ex){
00441 ROS_ERROR("%s",ex.what());
00442 cmd_robot.vector.x = 0.0f;
00443 cmd_robot.vector.y = 0.0f;
00444 }
00445
00446
00447 try
00448 {
00449 if ( std::isnan(cmd_robot.vector.x) || std::isnan(cmd_robot.vector.y) || std::isnan(theta) )
00450 {
00451 std::string err = "linear_nav: Output velocity contains NaN!";
00452 throw err;
00453 }
00454 if ( ! ( fabs(cmd_robot.vector.x) < 5.0 && fabs(cmd_robot.vector.y) < 5.0 && fabs(theta) < M_PI ) )
00455 {
00456 std::string err = "linear_nav: Output velocity too high";
00457 throw err;
00458 }
00459 }
00460 catch ( std::string err )
00461 {
00462 ROS_FATAL("%s", err.c_str());
00463 ros::shutdown();
00464 }
00465
00466
00467 msg.linear = cmd_robot.vector;
00468 msg.angular.z = theta;
00469 msg.linear.z = 0.0; msg.angular.x = 0.0; msg.angular.y = 0.0;
00470
00471 topic_pub_command_.publish(msg);
00472 }
00473
00474 void NodeClass::stopMovement() {
00475 publishVelocitiesGlobal(0.0f, 0.0f, 0.0f);
00476 vx_last_ = 0.0f;
00477 vy_last_ = 0.0f;
00478 vtheta_last_ = 0.0f;
00479 }
00480
00481 bool NodeClass::notMovingDueToObstacle() {
00482 if (move_ == true &&
00483 finished_ == false &&
00484 fabs(robot_twist_linear_robot_.vector.x) <= 0.01 &&
00485 fabs(robot_twist_linear_robot_.vector.y) <= 0.01 &&
00486 fabs(robot_twist_angular_robot_.vector.z) <= 0.01 &&
00487 ros::Time::now().toSec() - last_time_moving_ > goal_abortion_time_ )
00488 {
00489 return true;
00490 } else if ( fabs(robot_twist_linear_robot_.vector.x) > 0.01 ||
00491 fabs(robot_twist_linear_robot_.vector.y) > 0.01 ||
00492 fabs(robot_twist_angular_robot_.vector.z) > 0.01 )
00493 {
00494 last_time_moving_ = ros::Time::now().toSec();
00495 }
00496
00497 return false;
00498
00499 }
00500
00501 bool NodeClass::goalValid(const geometry_msgs::Pose & goal)
00502 {
00503 if( goal.orientation.x == 0.0 &&
00504 goal.orientation.y == 0.0 &&
00505 goal.orientation.z == 0.0 &&
00506 goal.orientation.w == 0.0 )
00507 {
00508 ROS_WARN("Goal invalid! Received Quaternion with all values 0.0!");
00509 return false;
00510 }
00511 else
00512 {
00513 return true;
00514 }
00515 }
00516
00517 void NodeClass::performControllerStep() {
00518 pthread_mutex_lock(&m_mutex);
00519
00520 double dt;
00521 double F_x, F_y, F_theta;
00522 double distance_to_goal;
00523 double theta, theta_goal;
00524 double cmd_vx, cmd_vy, cmd_vtheta;
00525 double vx_d, vy_d, vtheta_d, v_factor;
00526 double v_max_goal = v_max_;
00527
00528 if(!move_) {
00529 if(!use_move_action_)
00530 last_time_ = ros::Time::now().toSec();
00531 pthread_mutex_unlock(&m_mutex);
00532 return;
00533 }
00534
00535 getRobotPoseGlobal();
00536
00537 distance_to_goal = getDistance2d(robot_pose_global_, goal_pose_global_);
00538 theta = tf::getYaw(robot_pose_global_.pose.orientation);
00539 theta_goal = tf::getYaw(goal_pose_global_.pose.orientation);
00540
00541
00542 if( distance_to_goal <= goal_threshold_ &&
00543 sqrt(vx_last_ * vx_last_ + vy_last_ * vy_last_) <= speed_threshold_ &&
00544 fabs(getThetaDiffRad(theta_goal, theta)) <= goal_threshold_rot_ &&
00545 fabs(vtheta_last_) <= speed_threshold_rot_ )
00546 {
00547 finished_ = true;
00548 move_ = false;
00549 stopMovement();
00550 if(!use_move_action_)
00551 last_time_ = ros::Time::now().toSec();
00552 pthread_mutex_unlock(&m_mutex);
00553 return;
00554 } else if( notMovingDueToObstacle() == true ) {
00555 finished_ = false;
00556 move_ = false;
00557 stopMovement();
00558 if(use_move_action_)
00559 {
00560 as_.setAborted(move_base_msgs::MoveBaseResult(), "Cancel the goal because an obstacle is blocking the path.");
00561 }
00562 else
00563 {
00564 last_time_ = ros::Time::now().toSec();
00565 }
00566 ROS_INFO("Cancel the goal because an obstacle is blocking the path.");
00567 pthread_mutex_unlock(&m_mutex);
00568 return;
00569 } else finished_ = false;
00570
00571 dt = ros::Time::now().toSec() - last_time_;
00572 last_time_ = ros::Time::now().toSec();
00573
00574
00575 if(distance_to_goal < slow_down_distance_) {
00576
00577 double goal_linear_slope = v_max_ / slow_down_distance_;
00578 v_max_goal = distance_to_goal * goal_linear_slope;
00579
00580 if(v_max_goal > v_max_) v_max_goal = v_max_;
00581 else if(v_max_goal < 0.0f) v_max_goal = 0.0f;
00582 }
00583
00584
00585
00586 vx_d = kp_/kv_ * (goal_pose_global_.pose.position.x - robot_pose_global_.pose.position.x);
00587 vy_d = kp_/kv_ * (goal_pose_global_.pose.position.y - robot_pose_global_.pose.position.y);
00588 v_factor = v_max_goal / sqrt(vy_d*vy_d + vx_d*vx_d);
00589
00590 if(v_factor > 1.0) v_factor = 1.0;
00591
00592 F_x = - kv_ * vx_last_ + v_factor * kp_ * (goal_pose_global_.pose.position.x - robot_pose_global_.pose.position.x);
00593 F_y = - kv_ * vy_last_ + v_factor * kp_ * (goal_pose_global_.pose.position.y - robot_pose_global_.pose.position.y);
00594
00595 cmd_vx = vx_last_ + F_x / virt_mass_ * dt;
00596 cmd_vy = vy_last_ + F_y / virt_mass_ * dt;
00597
00598
00599
00600 vtheta_d = kp_rot_ / kv_rot_ * getThetaDiffRad(theta_goal, theta);
00601 v_factor = fabs(vtheta_max_ / vtheta_d);
00602 if(v_factor > 1.0) v_factor = 1.0;
00603
00604 F_theta = - kv_rot_ * vtheta_last_ + v_factor * kp_rot_ * getThetaDiffRad(theta_goal, theta);
00605 cmd_vtheta = vtheta_last_ + F_theta / virt_mass_rot_ * dt;
00606
00607
00608
00609 x_last_ = robot_pose_global_.pose.position.x;
00610 y_last_ = robot_pose_global_.pose.position.y;
00611 theta_last_ = theta;
00612 vx_last_ = cmd_vx;
00613 vy_last_ = cmd_vy;
00614 vtheta_last_ = cmd_vtheta;
00615
00616 publishVelocitiesGlobal(cmd_vx, cmd_vy, cmd_vtheta);
00617 pthread_mutex_unlock(&m_mutex);
00618 }
00619
00620
00621
00622
00623
00624 int main(int argc, char** argv)
00625 {
00626
00627 ros::init(argc, argv, "cob_linear");
00628
00629
00630 NodeClass nodeClass("move_base_linear");
00631
00632 if(nodeClass.getUseMoveAction())
00633 {
00634 ros::spin();
00635 }
00636 else
00637 {
00638 ros::Rate loop_rate(100);
00639 while(nodeClass.nh_.ok())
00640 {
00641 nodeClass.performControllerStep();
00642 loop_rate.sleep();
00643 ros::spinOnce();
00644 }
00645 }
00646
00647 return 0;
00648 }
00649