37 #include <nav_msgs/Path.h>
46 PoseFollower::~PoseFollower() {
53 costmap_ros_ = costmap_ros;
54 current_waypoint_ = 0;
58 collision_planner_.initialize(name +
"/collision_planner", tf_, costmap_ros_);
61 node_private.param(
"holonomic", holonomic_,
true);
63 global_plan_pub_ = node_private.advertise<nav_msgs::Path>(
"global_plan", 1);
66 odom_sub_ = node.subscribe<nav_msgs::Odometry>(
"odom", 1, boost::bind(&PoseFollower::odomCallback,
this, _1));
68 dsrv_ =
new dynamic_reconfigure::Server<pose_follower::PoseFollowerConfig>(
70 dynamic_reconfigure::Server<pose_follower::PoseFollowerConfig>::CallbackType cb =
71 boost::bind(&PoseFollower::reconfigureCB,
this, _1, _2);
72 dsrv_->setCallback(cb);
77 void PoseFollower::reconfigureCB(pose_follower::PoseFollowerConfig &config, uint32_t level) {
78 max_vel_lin_ = config.max_vel_lin;
79 max_vel_th_ = config.max_vel_th;
80 min_vel_lin_ = config.min_vel_lin;
81 min_vel_th_ = config.min_vel_th;
82 min_in_place_vel_th_ = config.min_in_place_vel_th;
83 in_place_trans_vel_ = config.in_place_trans_vel;
84 trans_stopped_velocity_ = config.trans_stopped_velocity;
85 rot_stopped_velocity_ = config.rot_stopped_velocity;
87 tolerance_trans_ = config.tolerance_trans;
88 tolerance_rot_ = config.tolerance_rot;
89 tolerance_timeout_ = config.tolerance_timeout;
91 samples_ = config.samples;
92 allow_backwards_ = config.allow_backwards;
93 turn_in_place_first_ = config.turn_in_place_first;
94 max_heading_diff_before_moving_ = config.max_heading_diff_before_moving;
96 K_trans_ = config.k_trans;
97 K_rot_ = config.k_rot;
100 void PoseFollower::odomCallback(
const nav_msgs::Odometry::ConstPtr& msg){
102 boost::mutex::scoped_lock lock(odom_lock_);
103 base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
104 base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
105 base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
106 ROS_DEBUG(
"In the odometry callback with velocity values: (%.2f, %.2f, %.2f)",
107 base_odom_.twist.twist.linear.x, base_odom_.twist.twist.linear.y, base_odom_.twist.twist.angular.z);
110 double PoseFollower::headingDiff(
double x,
double y,
double pt_x,
double pt_y,
double heading)
112 double v1_x = x - pt_x;
113 double v1_y = y - pt_y;
114 double v2_x = cos(heading);
115 double v2_y = sin(heading);
117 double perp_dot = v1_x * v2_y - v1_y * v2_x;
118 double dot = v1_x * v2_x + v1_y * v2_y;
121 double vector_angle = atan2(perp_dot, dot);
123 return -1.0 * vector_angle;
126 bool PoseFollower::stopped(){
128 nav_msgs::Odometry base_odom;
130 boost::mutex::scoped_lock lock(odom_lock_);
131 base_odom = base_odom_;
134 return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity_
135 && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity_
136 && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity_;
139 void PoseFollower::publishPlan(
const std::vector<geometry_msgs::PoseStamped> &path,
146 nav_msgs::Path gui_path;
147 gui_path.poses.resize(path.size());
148 gui_path.header.frame_id = path[0].header.frame_id;
149 gui_path.header.stamp = path[0].header.stamp;
152 for (
unsigned int i = 0; i < path.size(); i++) {
153 gui_path.poses[i] = path[i];
158 bool PoseFollower::computeVelocityCommands(geometry_msgs::Twist& cmd_vel){
160 geometry_msgs::PoseStamped robot_pose;
161 if(!costmap_ros_->getRobotPose(robot_pose)){
163 geometry_msgs::Twist empty_twist;
164 cmd_vel = empty_twist;
169 geometry_msgs::PoseStamped target_pose = global_plan_[current_waypoint_];
170 ROS_DEBUG(
"PoseFollower: current robot pose %f %f ==> %f", robot_pose.pose.position.x, robot_pose.pose.position.y,
tf2::getYaw(robot_pose.pose.orientation));
171 ROS_DEBUG(
"PoseFollower: target robot pose %f %f ==> %f", target_pose.pose.position.x, target_pose.pose.position.y,
tf2::getYaw(target_pose.pose.orientation));
174 geometry_msgs::Twist diff = diff2D(target_pose.pose, robot_pose.pose);
175 ROS_DEBUG(
"PoseFollower: diff %f %f ==> %f", diff.linear.x, diff.linear.y, diff.angular.z);
177 geometry_msgs::Twist limit_vel = limitTwist(diff);
179 geometry_msgs::Twist test_vel = limit_vel;
180 bool legal_traj = collision_planner_.checkTrajectory(test_vel.linear.x, test_vel.linear.y, test_vel.angular.z,
true);
182 double scaling_factor = 1.0;
183 double ds = scaling_factor / samples_;
187 for(
int i = 0; i < samples_; ++i){
188 test_vel.linear.x = limit_vel.linear.x * scaling_factor;
189 test_vel.linear.y = limit_vel.linear.y * scaling_factor;
190 test_vel.angular.z = limit_vel.angular.z * scaling_factor;
191 test_vel = limitTwist(test_vel);
192 if(collision_planner_.checkTrajectory(test_vel.linear.x, test_vel.linear.y, test_vel.angular.z,
false)){
196 scaling_factor -= ds;
201 ROS_ERROR(
"Not legal (%.2f, %.2f, %.2f)", limit_vel.linear.x, limit_vel.linear.y, limit_vel.angular.z);
202 geometry_msgs::Twist empty_twist;
203 cmd_vel = empty_twist;
210 bool in_goal_position =
false;
211 while(fabs(diff.linear.x) <= tolerance_trans_ &&
212 fabs(diff.linear.y) <= tolerance_trans_ &&
213 fabs(diff.angular.z) <= tolerance_rot_)
215 if(current_waypoint_ < global_plan_.size() - 1)
218 target_pose = global_plan_[current_waypoint_];
219 diff = diff2D(target_pose.pose, robot_pose.pose);
223 ROS_INFO(
"Reached goal: %d", current_waypoint_);
224 in_goal_position =
true;
230 if(!in_goal_position)
235 geometry_msgs::Twist empty_twist;
236 cmd_vel = empty_twist;
242 bool PoseFollower::setPlan(
const std::vector<geometry_msgs::PoseStamped>& global_plan){
243 current_waypoint_ = 0;
245 if(!
transformGlobalPlan(*tf_, global_plan, *costmap_ros_, costmap_ros_->getGlobalFrameID(), global_plan_)){
246 ROS_ERROR(
"Could not transform the global plan to the frame of the controller");
250 ROS_DEBUG(
"global plan size: %lu", global_plan_.size());
255 bool PoseFollower::isGoalReached(){
259 geometry_msgs::Twist PoseFollower::diff2D(
const geometry_msgs::Pose& pose1_msg,
260 const geometry_msgs::Pose& pose2_msg)
265 geometry_msgs::Twist res;
271 if(holonomic_ || (fabs(res.linear.x) <= tolerance_trans_ && fabs(res.linear.y) <= tolerance_trans_))
282 if (allow_backwards_)
288 if(fabs(neg_yaw_diff) < fabs(yaw_diff)){
289 ROS_DEBUG(
"Negative is better: %.2f", neg_yaw_diff);
290 yaw_diff = neg_yaw_diff;
296 rot_diff.
setRPY(0.0, 0.0, yaw_diff);
301 diff = pose2.
inverse() * new_pose;
309 geometry_msgs::Twist PoseFollower::limitTwist(
const geometry_msgs::Twist& twist)
311 geometry_msgs::Twist res = twist;
312 res.linear.x *= K_trans_;
316 res.linear.y *= K_trans_;
317 res.angular.z *= K_rot_;
320 if (turn_in_place_first_ && fabs(twist.angular.z) > max_heading_diff_before_moving_)
324 if (fabs(res.angular.z) > max_vel_th_) res.angular.z = max_vel_th_ *
sign(res.angular.z);
325 if (fabs(res.angular.z) < min_in_place_vel_th_) res.angular.z = min_in_place_vel_th_ *
sign(res.angular.z);
330 double lin_overshoot = sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y) / max_vel_lin_;
331 double lin_undershoot = min_vel_lin_ / sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y);
332 if (lin_overshoot > 1.0)
334 res.linear.x /= lin_overshoot;
335 res.linear.y /= lin_overshoot;
339 if(lin_undershoot > 1.0)
341 res.linear.x *= lin_undershoot;
342 res.linear.y *= lin_undershoot;
345 if (fabs(res.angular.z) > max_vel_th_) res.angular.z = max_vel_th_ *
sign(res.angular.z);
346 if (fabs(res.angular.z) < min_vel_th_) res.angular.z = min_vel_th_ *
sign(res.angular.z);
347 if (std::isnan(res.linear.x))
349 if (std::isnan(res.linear.y))
353 if(sqrt(twist.linear.x * twist.linear.x + twist.linear.y * twist.linear.y) < in_place_trans_vel_){
354 if (fabs(res.angular.z) < min_in_place_vel_th_) res.angular.z = min_in_place_vel_th_ *
sign(res.angular.z);
359 ROS_DEBUG(
"Angular command %f", res.angular.z);
363 bool PoseFollower::transformGlobalPlan(
const tf2_ros::Buffer&
tf,
const std::vector<geometry_msgs::PoseStamped>& global_plan,
365 std::vector<geometry_msgs::PoseStamped>& transformed_plan){
366 const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
368 transformed_plan.clear();
371 if (global_plan.empty())
373 ROS_ERROR(
"Recieved plan with zero length");
377 geometry_msgs::TransformStamped transform;
378 transform =
tf.lookupTransform(global_frame,
ros::Time(),
379 plan_pose.header.frame_id, plan_pose.header.stamp,
380 plan_pose.header.frame_id);
385 geometry_msgs::PoseStamped newer_pose;
387 for(
unsigned int i = 0; i < global_plan.size(); ++i){
388 const geometry_msgs::PoseStamped& pose = global_plan[i];
390 tf_pose.
setData(tf_transform * tf_pose);
391 tf_pose.stamp_ = tf_transform.
stamp_;
392 tf_pose.frame_id_ = global_frame;
395 transformed_plan.push_back(newer_pose);
399 ROS_ERROR(
"No Transform available Error: %s\n", ex.what());
403 ROS_ERROR(
"Connectivity Error: %s\n", ex.what());
407 ROS_ERROR(
"Extrapolation Error: %s\n", ex.what());
408 if (!global_plan.empty())
409 ROS_ERROR(
"Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (
unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str());