44 #include <boost/algorithm/string.hpp>
47 #include <mbf_msgs/ExePathResult.h>
52 #include "g2o/core/sparse_optimizer.h"
53 #include "g2o/core/block_solver.h"
54 #include "g2o/core/factory.h"
55 #include "g2o/core/optimization_algorithm_gauss_newton.h"
56 #include "g2o/core/optimization_algorithm_levenberg.h"
57 #include "g2o/solvers/csparse/linear_solver_csparse.h"
58 #include "g2o/solvers/cholmod/linear_solver_cholmod.h"
70 costmap_converter_loader_(
"costmap_converter",
"costmap_converter::BaseCostmapToPolygons"),
71 dynamic_recfg_(NULL), custom_via_points_active_(false), goal_reached_(false), no_infeasible_plans_(0),
72 last_preferred_rotdir_(
RotType::
none), initialized_(false)
118 ROS_INFO(
"Parallel planning in distinctive topologies enabled.");
123 ROS_INFO(
"Parallel planning in distinctive topologies disabled.");
145 boost::replace_all(converter_name,
"::",
"/");
155 ROS_WARN(
"The specified costmap converter plugin cannot be loaded. All occupied costmap cells are treaten as point obstacles. Error message: %s", ex.what());
160 ROS_INFO(
"No costmap conversion plugin specified. All occupied costmap cells are treaten as point obstacles.");
171 dynamic_recfg_ = boost::make_shared< dynamic_reconfigure::Server<TebLocalPlannerReconfigureConfig> >(nh);
186 double controller_frequency = 5;
187 nh_move_base.param(
"controller_frequency", controller_frequency, controller_frequency);
193 ROS_DEBUG(
"teb_local_planner plugin initialized.");
197 ROS_WARN(
"teb_local_planner has already been initialized, doing nothing.");
208 ROS_ERROR(
"teb_local_planner has not been initialized, please call initialize() before using this planner");
228 std::string dummy_message;
229 geometry_msgs::PoseStamped dummy_pose;
230 geometry_msgs::TwistStamped dummy_velocity, cmd_vel_stamped;
232 cmd_vel = cmd_vel_stamped.twist;
233 return outcome == mbf_msgs::ExePathResult::SUCCESS;
237 const geometry_msgs::TwistStamped& velocity,
238 geometry_msgs::TwistStamped &cmd_vel,
239 std::string &message)
244 ROS_ERROR(
"teb_local_planner has not been initialized, please call initialize() before using this planner");
245 message =
"teb_local_planner has not been initialized";
246 return mbf_msgs::ExePathResult::NOT_INITIALIZED;
249 static uint32_t seq = 0;
250 cmd_vel.header.seq = seq++;
253 cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
257 geometry_msgs::PoseStamped robot_pose;
262 geometry_msgs::PoseStamped robot_vel_tf;
264 robot_vel_.linear.x = robot_vel_tf.pose.position.x;
265 robot_vel_.linear.y = robot_vel_tf.pose.position.y;
272 std::vector<geometry_msgs::PoseStamped> transformed_plan;
274 geometry_msgs::TransformStamped tf_plan_to_global;
276 transformed_plan, &goal_idx, &tf_plan_to_global))
278 ROS_WARN(
"Could not transform the global plan to the frame of the controller");
279 message =
"Could not transform the global plan to the frame of the controller";
280 return mbf_msgs::ExePathResult::INTERNAL_ERROR;
287 nav_msgs::Odometry base_odom;
291 geometry_msgs::PoseStamped global_goal;
293 double dx = global_goal.pose.position.x -
robot_pose_.
x();
294 double dy = global_goal.pose.position.y -
robot_pose_.
y();
303 return mbf_msgs::ExePathResult::SUCCESS;
311 if (transformed_plan.empty())
313 ROS_WARN(
"Transformed plan is empty. Cannot determine a local plan.");
314 message =
"Transformed plan is empty";
315 return mbf_msgs::ExePathResult::INVALID_PATH;
319 robot_goal_.
x() = transformed_plan.back().pose.position.x;
320 robot_goal_.
y() = transformed_plan.back().pose.position.y;
328 tf2::convert(q, transformed_plan.back().pose.orientation);
336 if (transformed_plan.size()==1)
338 transformed_plan.insert(transformed_plan.begin(), geometry_msgs::PoseStamped());
340 transformed_plan.front() = robot_pose;
364 ROS_WARN(
"teb_local_planner was not able to obtain a local plan for the current setting.");
369 message =
"teb_local_planner was not able to obtain a local plan";
370 return mbf_msgs::ExePathResult::NO_VALID_CMD;
376 cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
380 ROS_WARN_THROTTLE(1.0,
"TebLocalPlannerROS: the trajectory has diverged. Resetting planner...");
385 return mbf_msgs::ExePathResult::NO_VALID_CMD;
399 cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
403 ROS_WARN(
"TebLocalPlannerROS: trajectory is not feasible. Resetting planner...");
408 message =
"teb_local_planner trajectory is not feasible";
409 return mbf_msgs::ExePathResult::NO_VALID_CMD;
417 ROS_WARN(
"TebLocalPlannerROS: velocity command invalid. Resetting planner...");
421 message =
"teb_local_planner velocity command invalid";
422 return mbf_msgs::ExePathResult::NO_VALID_CMD;
426 saturateVelocity(cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z,
437 if (!std::isfinite(cmd_vel.twist.angular.z))
439 cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
442 ROS_WARN(
"TebLocalPlannerROS: Resulting steering angle is not finite. Resetting planner...");
445 message =
"teb_local_planner steering angle is not finite";
446 return mbf_msgs::ExePathResult::NO_VALID_CMD;
461 return mbf_msgs::ExePathResult::SUCCESS;
516 for (std::size_t i=0; i<obstacles->obstacles.size(); ++i)
518 const costmap_converter::ObstacleMsg* obstacle = &obstacles->obstacles.at(i);
519 const geometry_msgs::Polygon* polygon = &obstacle->polygon;
521 if (polygon->points.size()==1 && obstacle->radius > 0)
525 else if (polygon->points.size()==1)
529 else if (polygon->points.size()==2)
532 polygon->points[1].x, polygon->points[1].y )));
534 else if (polygon->points.size()>2)
537 for (std::size_t j=0; j<polygon->points.size(); ++j)
539 polyobst->
pushBackVertex(polygon->points[j].x, polygon->points[j].y);
547 obstacles_.back()->setCentroidVelocity(obstacles->obstacles[i].velocities, obstacles->obstacles[i].orientation);
560 Eigen::Affine3d obstacle_to_map_eig;
571 obstacle_to_map_eig.setIdentity();
599 (obstacle_to_map_eig *
line_end).head(2) )));
603 ROS_WARN(
"Invalid custom obstacle received. List of polygon vertices is empty. Skipping...");
608 PolygonObstacle* polyobst =
new PolygonObstacle;
614 polyobst->pushBackVertex( (obstacle_to_map_eig * pos).head(2) );
616 polyobst->finalizePolygon();
631 if (min_separation<=0)
634 std::size_t prev_idx = 0;
635 for (std::size_t i=1; i < transformed_plan.size(); ++i)
638 if (
distance_points2d( transformed_plan[prev_idx].pose.position, transformed_plan[i].pose.position ) < min_separation)
642 via_points_.push_back( Eigen::Vector2d( transformed_plan[i].pose.position.x, transformed_plan[i].pose.position.y ) );
659 if (global_plan.empty())
665 geometry_msgs::TransformStamped global_to_plan_transform =
tf.lookupTransform(global_plan.front().header.frame_id, global_pose.header.frame_id,
ros::Time(0));
666 geometry_msgs::PoseStamped robot;
669 double dist_thresh_sq = dist_behind_robot*dist_behind_robot;
672 std::vector<geometry_msgs::PoseStamped>::iterator it = global_plan.begin();
673 std::vector<geometry_msgs::PoseStamped>::iterator erase_end = it;
674 while (it != global_plan.end())
676 double dx = robot.pose.position.x - it->pose.position.x;
677 double dy = robot.pose.position.y - it->pose.position.y;
678 double dist_sq = dx * dx + dy * dy;
679 if (dist_sq < dist_thresh_sq)
686 if (erase_end == global_plan.end())
689 if (erase_end != global_plan.begin())
690 global_plan.erase(global_plan.begin(), erase_end);
694 ROS_DEBUG(
"Cannot prune path since no transform is available: %s\n", ex.what());
702 const geometry_msgs::PoseStamped& global_pose,
const costmap_2d::Costmap2D& costmap,
const std::string& global_frame,
double max_plan_length,
703 std::vector<geometry_msgs::PoseStamped>& transformed_plan,
int* current_goal_idx, geometry_msgs::TransformStamped* tf_plan_to_global)
const
707 const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
709 transformed_plan.clear();
713 if (global_plan.empty())
715 ROS_ERROR(
"Received plan with zero length");
716 *current_goal_idx = 0;
721 geometry_msgs::TransformStamped plan_to_global_transform =
tf.lookupTransform(global_frame,
ros::Time(), plan_pose.header.frame_id, plan_pose.header.stamp,
725 geometry_msgs::PoseStamped robot_pose;
726 tf.transform(global_pose, robot_pose, plan_pose.header.frame_id);
731 dist_threshold *= 0.85;
736 double sq_dist_threshold = dist_threshold * dist_threshold;
737 double sq_dist = 1e10;
740 bool robot_reached =
false;
741 for(
int j=0; j < (int)global_plan.size(); ++j)
743 double x_diff = robot_pose.pose.position.x - global_plan[j].pose.position.x;
744 double y_diff = robot_pose.pose.position.y - global_plan[j].pose.position.y;
745 double new_sq_dist = x_diff * x_diff + y_diff * y_diff;
747 if (robot_reached && new_sq_dist > sq_dist)
750 if (new_sq_dist < sq_dist)
752 sq_dist = new_sq_dist;
755 robot_reached =
true;
759 geometry_msgs::PoseStamped newer_pose;
761 double plan_length = 0;
764 while(i < (
int)global_plan.size() && sq_dist <= sq_dist_threshold && (max_plan_length<=0 || plan_length <= max_plan_length))
766 const geometry_msgs::PoseStamped& pose = global_plan[i];
769 transformed_plan.push_back(newer_pose);
771 double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x;
772 double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y;
773 sq_dist = x_diff * x_diff + y_diff * y_diff;
776 if (i>0 && max_plan_length>0)
777 plan_length +=
distance_points2d(global_plan[i-1].pose.position, global_plan[i].pose.position);
784 if (transformed_plan.empty())
788 transformed_plan.push_back(newer_pose);
791 if (current_goal_idx) *current_goal_idx = int(global_plan.size())-1;
796 if (current_goal_idx) *current_goal_idx = i-1;
800 if (tf_plan_to_global) *tf_plan_to_global = plan_to_global_transform;
804 ROS_ERROR(
"No Transform available Error: %s\n", ex.what());
809 ROS_ERROR(
"Connectivity Error: %s\n", ex.what());
814 ROS_ERROR(
"Extrapolation Error: %s\n", ex.what());
815 if (global_plan.size() > 0)
816 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());
828 int current_goal_idx,
const geometry_msgs::TransformStamped& tf_plan_to_global,
int moving_average_length)
const
830 int n = (int)global_plan.size();
833 if (current_goal_idx > n-moving_average_length-2)
835 if (current_goal_idx >= n-1)
842 tf2::convert(global_plan.back().pose.orientation, global_orientation);
844 tf2::convert(tf_plan_to_global.transform.rotation, rotation);
851 moving_average_length = std::min(moving_average_length, n-current_goal_idx-1 );
853 std::vector<double> candidates;
854 geometry_msgs::PoseStamped tf_pose_k = local_goal;
855 geometry_msgs::PoseStamped tf_pose_kp1;
857 int range_end = current_goal_idx + moving_average_length;
858 for (
int i = current_goal_idx; i < range_end; ++i)
864 candidates.push_back( std::atan2(tf_pose_kp1.pose.position.y - tf_pose_k.pose.position.y,
865 tf_pose_kp1.pose.position.x - tf_pose_k.pose.position.x ) );
868 tf_pose_k = tf_pose_kp1;
875 double max_vel_x_backwards)
const
877 double ratio_x = 1, ratio_omega = 1, ratio_y = 1;
880 ratio_x = max_vel_x / vx;
883 if (vy > max_vel_y || vy < -max_vel_y)
884 ratio_y = std::abs(max_vel_y / vy);
887 if (omega > max_vel_theta || omega < -max_vel_theta)
888 ratio_omega = std::abs(max_vel_theta / omega);
891 if (max_vel_x_backwards<=0)
893 ROS_WARN_ONCE(
"TebLocalPlannerROS(): Do not choose max_vel_x_backwards to be <=0. Disable backwards driving by increasing the optimization weight for penalyzing backwards driving.");
895 else if (vx < -max_vel_x_backwards)
896 ratio_x = - max_vel_x_backwards / vx;
900 double ratio = std::min(std::min(ratio_x, ratio_y), ratio_omega);
909 omega *= ratio_omega;
912 double vel_linear = std::hypot(vx, vy);
913 if (vel_linear > max_vel_trans)
915 double max_vel_trans_ratio = max_vel_trans / vel_linear;
916 vx *= max_vel_trans_ratio;
917 vy *= max_vel_trans_ratio;
924 if (omega==0 || v==0)
927 double radius = v/omega;
929 if (fabs(radius) < min_turning_radius)
930 radius = double(g2o::sign(radius)) * min_turning_radius;
938 ROS_WARN_COND(opt_inscribed_radius + min_obst_dist < costmap_inscribed_radius,
939 "The inscribed radius of the footprint specified for TEB optimization (%f) + min_obstacle_dist (%f) are smaller "
940 "than the inscribed radius of the robot's footprint in the costmap parameters (%f, including 'footprint_padding'). "
941 "Infeasible optimziation results might occur frequently!", opt_inscribed_radius, min_obst_dist, costmap_inscribed_radius);
952 goal_idx < (
int)transformed_plan.size()-1 &&
960 int horizon_reduction = goal_idx/2;
965 horizon_reduction /= 2;
971 int new_goal_idx_transformed_plan = int(transformed_plan.size()) - horizon_reduction - 1;
972 goal_idx -= horizon_reduction;
973 if (new_goal_idx_transformed_plan>0 && goal_idx >= 0)
974 transformed_plan.erase(transformed_plan.begin()+new_goal_idx_transformed_plan, transformed_plan.end());
976 goal_idx += horizon_reduction;
983 double max_vel_theta;
998 if (!recently_oscillated)
1005 ROS_WARN(
"TebLocalPlannerROS: possible oscillation (of the robot or its local plan) detected. Activating recovery strategy (prefer current turning direction during optimization).");
1014 ROS_INFO(
"TebLocalPlannerROS: oscillation recovery disabled/expired.");
1028 ROS_INFO_ONCE(
"Via-points received. This message is printed once.");
1031 ROS_WARN(
"Via-points are already obtained from the global plan (global_plan_viapoint_sep>0)."
1032 "Ignoring custom via-points.");
1039 for (
const geometry_msgs::PoseStamped& pose : via_points_msg->poses)
1041 via_points_.emplace_back(pose.pose.position.x, pose.pose.position.y);
1048 std::string model_name;
1049 if (!nh.
getParam(
"footprint_model/type", model_name))
1051 ROS_INFO(
"No robot footprint model specified for trajectory optimization. Using point-shaped model.");
1052 return boost::make_shared<PointRobotFootprint>();
1056 if (model_name.compare(
"point") == 0)
1058 ROS_INFO(
"Footprint model 'point' loaded for trajectory optimization.");
1059 return boost::make_shared<PointRobotFootprint>(
config.obstacles.min_obstacle_dist);
1063 if (model_name.compare(
"circular") == 0)
1067 if (!nh.
getParam(
"footprint_model/radius", radius))
1070 <<
"/footprint_model/radius' does not exist. Using point-model instead.");
1071 return boost::make_shared<PointRobotFootprint>();
1073 ROS_INFO_STREAM(
"Footprint model 'circular' (radius: " << radius <<
"m) loaded for trajectory optimization.");
1074 return boost::make_shared<CircularRobotFootprint>(radius);
1078 if (model_name.compare(
"line") == 0)
1081 if (!nh.
hasParam(
"footprint_model/line_start") || !nh.
hasParam(
"footprint_model/line_end"))
1084 <<
"/footprint_model/line_start' and/or '.../line_end' do not exist. Using point-model instead.");
1085 return boost::make_shared<PointRobotFootprint>();
1094 <<
"/footprint_model/line_start' and/or '.../line_end' do not contain x and y coordinates (2D). Using point-model instead.");
1095 return boost::make_shared<PointRobotFootprint>();
1099 <<
line_end[0] <<
"," <<
line_end[1] <<
"]m) loaded for trajectory optimization.");
1100 return boost::make_shared<LineRobotFootprint>(Eigen::Map<const Eigen::Vector2d>(
line_start.data()), Eigen::Map<const Eigen::Vector2d>(
line_end.data()),
config.obstacles.min_obstacle_dist);
1104 if (model_name.compare(
"two_circles") == 0)
1107 if (!nh.
hasParam(
"footprint_model/front_offset") || !nh.
hasParam(
"footprint_model/front_radius")
1108 || !nh.
hasParam(
"footprint_model/rear_offset") || !nh.
hasParam(
"footprint_model/rear_radius"))
1111 <<
"/footprint_model/front_offset', '.../front_radius', '.../rear_offset' and '.../rear_radius' do not exist. Using point-model instead.");
1112 return boost::make_shared<PointRobotFootprint>();
1114 double front_offset, front_radius, rear_offset, rear_radius;
1115 nh.
getParam(
"footprint_model/front_offset", front_offset);
1116 nh.
getParam(
"footprint_model/front_radius", front_radius);
1117 nh.
getParam(
"footprint_model/rear_offset", rear_offset);
1118 nh.
getParam(
"footprint_model/rear_radius", rear_radius);
1119 ROS_INFO_STREAM(
"Footprint model 'two_circles' (front_offset: " << front_offset <<
"m, front_radius: " << front_radius
1120 <<
"m, rear_offset: " << rear_offset <<
"m, rear_radius: " << rear_radius <<
"m) loaded for trajectory optimization.");
1121 return boost::make_shared<TwoCirclesRobotFootprint>(front_offset, front_radius, rear_offset, rear_radius);
1125 if (model_name.compare(
"polygon") == 0)
1130 if (!nh.
getParam(
"footprint_model/vertices", footprint_xmlrpc) )
1133 <<
"/footprint_model/vertices' does not exist. Using point-model instead.");
1134 return boost::make_shared<PointRobotFootprint>();
1142 ROS_INFO_STREAM(
"Footprint model 'polygon' loaded for trajectory optimization.");
1143 return boost::make_shared<PolygonRobotFootprint>(polygon);
1145 catch(
const std::exception& ex)
1147 ROS_ERROR_STREAM(
"Footprint model 'polygon' cannot be loaded for trajectory optimization: " << ex.what() <<
". Using point-model instead.");
1148 return boost::make_shared<PointRobotFootprint>();
1154 <<
"/footprint_model/vertices' does not define an array of coordinates. Using point-model instead.");
1155 return boost::make_shared<PointRobotFootprint>();
1161 ROS_WARN_STREAM(
"Unknown robot footprint model specified with parameter '" << nh.
getNamespace() <<
"/footprint_model/type'. Using point model instead.");
1162 return boost::make_shared<PointRobotFootprint>();
1172 footprint_xmlrpc.
size() < 3)
1174 ROS_FATAL(
"The footprint must be specified as list of lists on the parameter server, %s was specified as %s",
1175 full_param_name.c_str(), std::string(footprint_xmlrpc).c_str());
1176 throw std::runtime_error(
"The footprint must be specified as list of lists on the parameter server with at least "
1177 "3 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
1183 for (
int i = 0; i < footprint_xmlrpc.
size(); ++i)
1190 ROS_FATAL(
"The footprint (parameter %s) must be specified as list of lists on the parameter server eg: "
1191 "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form.",
1192 full_param_name.c_str());
1193 throw std::runtime_error(
"The footprint must be specified as list of lists on the parameter server eg: "
1194 "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form");
1200 footprint.push_back(pt);
1211 std::string& value_string = value;
1212 ROS_FATAL(
"Values in the footprint specification (param %s) must be numbers. Found value %s.",
1213 full_param_name.c_str(), value_string.c_str());
1214 throw std::runtime_error(
"Values in the footprint specification must be numbers");