30 #include <boost/algorithm/string.hpp>
33 #include <mbf_msgs/ExePathResult.h>
45 : _costmap_ros(nullptr),
47 _costmap_model(nullptr),
48 _costmap_converter_loader(
"costmap_converter",
"costmap_converter::BaseCostmapToPolygons"),
51 _no_infeasible_plans(0),
120 ROS_ERROR(
"Controller configuration failed.");
135 boost::replace_all(converter_name,
"::",
"/");
147 "The specified costmap converter plugin cannot be loaded. All occupied costmap cells are treaten as point obstacles. Error "
154 ROS_INFO(
"No costmap conversion plugin specified. All occupied costmap cells are treaten as point obstacles.");
187 ROS_DEBUG(
"mpc_local_planner plugin initialized.");
191 ROS_WARN(
"mpc_local_planner has already been initialized, doing nothing.");
200 ROS_ERROR(
"mpc_local_planner has not been initialized, please call initialize() before using this planner");
219 std::string dummy_message;
220 geometry_msgs::PoseStamped dummy_pose;
221 geometry_msgs::TwistStamped dummy_velocity, cmd_vel_stamped;
223 cmd_vel = cmd_vel_stamped.twist;
224 return outcome == mbf_msgs::ExePathResult::SUCCESS;
228 geometry_msgs::TwistStamped& cmd_vel, std::string& message)
233 ROS_ERROR(
"mpc_local_planner has not been initialized, please call initialize() before using this planner");
234 message =
"mpc_local_planner has not been initialized";
235 return mbf_msgs::ExePathResult::NOT_INITIALIZED;
238 static uint32_t seq = 0;
239 cmd_vel.header.seq = seq++;
242 cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
246 geometry_msgs::PoseStamped robot_pose;
251 geometry_msgs::PoseStamped robot_vel_tf;
253 _robot_vel.linear.x = robot_vel_tf.pose.position.x;
254 _robot_vel.linear.y = robot_vel_tf.pose.position.y;
261 std::vector<geometry_msgs::PoseStamped> transformed_plan;
263 geometry_msgs::TransformStamped tf_plan_to_global;
265 &goal_idx, &tf_plan_to_global))
267 ROS_WARN(
"Could not transform the global plan to the frame of the controller");
268 message =
"Could not transform the global plan to the frame of the controller";
269 return mbf_msgs::ExePathResult::INTERNAL_ERROR;
276 geometry_msgs::PoseStamped global_goal;
278 double dx = global_goal.pose.position.x -
_robot_pose.
x();
279 double dy = global_goal.pose.position.y -
_robot_pose.
y();
284 return mbf_msgs::ExePathResult::SUCCESS;
288 if (transformed_plan.empty())
290 ROS_WARN(
"Transformed plan is empty. Cannot determine a local plan.");
291 message =
"Transformed plan is empty";
292 return mbf_msgs::ExePathResult::INVALID_PATH;
296 _robot_goal.
x() = transformed_plan.back().pose.position.x;
297 _robot_goal.
y() = transformed_plan.back().pose.position.y;
305 tf2::convert(q, transformed_plan.back().pose.orientation);
313 if (transformed_plan.size() == 1)
315 transformed_plan.insert(transformed_plan.begin(), geometry_msgs::PoseStamped());
317 transformed_plan.front() = robot_pose;
350 bool success =
false;
361 ROS_WARN(
"mpc_local_planner was not able to obtain a local plan for the current setting.");
366 message =
"mpc_local_planner was not able to obtain a local plan";
367 return mbf_msgs::ExePathResult::NO_VALID_CMD;
382 cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
386 ROS_WARN(
"MpcLocalPlannerROS: trajectory is not feasible. Resetting planner...");
390 message =
"mpc_local_planner trajectory is not feasible";
391 return mbf_msgs::ExePathResult::NO_VALID_CMD;
399 ROS_WARN(
"MpcLocalPlannerROS: velocity command invalid. Resetting controller...");
403 message =
"mpc_local_planner velocity command invalid";
404 return mbf_msgs::ExePathResult::NO_VALID_CMD;
424 return mbf_msgs::ExePathResult::SUCCESS;
471 if (!obstacles)
return;
473 for (std::size_t i = 0; i < obstacles->obstacles.size(); ++i)
475 const costmap_converter::ObstacleMsg* obstacle = &obstacles->obstacles.at(i);
476 const geometry_msgs::Polygon* polygon = &obstacle->polygon;
478 if (polygon->points.size() == 1 && obstacle->radius > 0)
482 else if (polygon->points.size() == 1)
486 else if (polygon->points.size() == 2)
489 ObstaclePtr(
new LineObstacle(polygon->points[0].x, polygon->points[0].y, polygon->points[1].x, polygon->points[1].y)));
491 else if (polygon->points.size() > 2)
494 for (std::size_t j = 0; j < polygon->points.size(); ++j)
496 polyobst->
pushBackVertex(polygon->points[j].x, polygon->points[j].y);
498 polyobst->finalizePolygon();
503 if (!
_obstacles.empty())
_obstacles.back()->setCentroidVelocity(obstacles->obstacles[i].velocities, obstacles->obstacles[i].orientation);
518 geometry_msgs::TransformStamped obstacle_to_map =
559 ROS_WARN(
"Invalid custom obstacle received. List of polygon vertices is empty. Skipping...");
570 polyobst->pushBackVertex((obstacle_to_map_eig * pos).
head(2));
572 polyobst->finalizePolygon();
587 if (min_separation <= 0)
return;
589 std::size_t prev_idx = 0;
590 for (std::size_t i = 1; i < transformed_plan.size(); ++i)
593 if (
distance_points2d(transformed_plan[prev_idx].pose.position, transformed_plan[i].pose.position) < min_separation)
continue;
596 _via_points.emplace_back(transformed_plan[i].pose);
610 std::vector<geometry_msgs::PoseStamped>& global_plan,
double dist_behind_robot)
612 if (global_plan.empty())
return true;
617 geometry_msgs::TransformStamped global_to_plan_transform =
618 tf.lookupTransform(global_plan.front().header.frame_id, global_pose.header.frame_id,
ros::Time(0));
619 geometry_msgs::PoseStamped robot;
622 double dist_thresh_sq = dist_behind_robot * dist_behind_robot;
625 std::vector<geometry_msgs::PoseStamped>::iterator it = global_plan.begin();
626 std::vector<geometry_msgs::PoseStamped>::iterator erase_end = it;
627 while (it != global_plan.end())
629 double dx = robot.pose.position.x - it->pose.position.x;
630 double dy = robot.pose.position.y - it->pose.position.y;
631 double dist_sq = dx * dx + dy * dy;
632 if (dist_sq < dist_thresh_sq)
639 if (erase_end == global_plan.end())
return false;
641 if (erase_end != global_plan.begin()) global_plan.erase(global_plan.begin(), erase_end);
645 ROS_DEBUG(
"Cannot prune path since no transform is available: %s\n", ex.what());
653 const std::string& global_frame,
double max_plan_length,
654 std::vector<geometry_msgs::PoseStamped>& transformed_plan,
int* current_goal_idx,
655 geometry_msgs::TransformStamped* tf_plan_to_global)
const
659 const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
661 transformed_plan.clear();
665 if (global_plan.empty())
667 ROS_ERROR(
"Received plan with zero length");
668 *current_goal_idx = 0;
673 geometry_msgs::TransformStamped plan_to_global_transform =
tf.lookupTransform(
674 global_frame,
ros::Time(), plan_pose.header.frame_id, plan_pose.header.stamp, plan_pose.header.frame_id,
ros::Duration(0.5));
677 geometry_msgs::PoseStamped robot_pose;
678 tf.transform(global_pose, robot_pose, plan_pose.header.frame_id);
681 double dist_threshold =
683 dist_threshold *= 0.85;
687 double sq_dist_threshold = dist_threshold * dist_threshold;
688 double sq_dist = 1e10;
691 for (
int j = 0; j < (
int)global_plan.size(); ++j)
693 double x_diff = robot_pose.pose.position.x - global_plan[j].pose.position.x;
694 double y_diff = robot_pose.pose.position.y - global_plan[j].pose.position.y;
695 double new_sq_dist = x_diff * x_diff + y_diff * y_diff;
696 if (new_sq_dist > sq_dist_threshold)
break;
698 if (new_sq_dist < sq_dist)
700 sq_dist = new_sq_dist;
705 geometry_msgs::PoseStamped newer_pose;
707 double plan_length = 0;
710 while (i < (
int)global_plan.size() && sq_dist <= sq_dist_threshold && (max_plan_length <= 0 || plan_length <= max_plan_length))
712 const geometry_msgs::PoseStamped& pose = global_plan[i];
715 transformed_plan.push_back(newer_pose);
717 double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x;
718 double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y;
719 sq_dist = x_diff * x_diff + y_diff * y_diff;
722 if (i > 0 && max_plan_length > 0)
730 if (transformed_plan.empty())
734 transformed_plan.push_back(newer_pose);
737 if (current_goal_idx) *current_goal_idx =
int(global_plan.size()) - 1;
742 if (current_goal_idx) *current_goal_idx = i - 1;
746 if (tf_plan_to_global) *tf_plan_to_global = plan_to_global_transform;
750 ROS_ERROR(
"No Transform available Error: %s\n", ex.what());
755 ROS_ERROR(
"Connectivity Error: %s\n", ex.what());
760 ROS_ERROR(
"Extrapolation Error: %s\n", ex.what());
761 if (global_plan.size() > 0)
762 ROS_ERROR(
"Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (
unsigned int)global_plan.size(),
763 global_plan[0].header.frame_id.c_str());
772 const geometry_msgs::PoseStamped& local_goal,
int current_goal_idx,
773 const geometry_msgs::TransformStamped& tf_plan_to_global,
int moving_average_length)
const
775 int n = (
int)global_plan.size();
778 if (current_goal_idx > n - moving_average_length - 2)
780 if (current_goal_idx >= n - 1)
787 tf2::convert(global_plan.back().pose.orientation, global_orientation);
789 tf2::convert(tf_plan_to_global.transform.rotation, rotation);
796 moving_average_length =
797 std::min(moving_average_length, n - current_goal_idx - 1);
799 std::vector<double> candidates;
800 geometry_msgs::PoseStamped tf_pose_k = local_goal;
801 geometry_msgs::PoseStamped tf_pose_kp1;
803 int range_end = current_goal_idx + moving_average_length;
804 for (
int i = current_goal_idx; i < range_end; ++i)
810 candidates.push_back(
811 std::atan2(tf_pose_kp1.pose.position.y - tf_pose_k.pose.position.y, tf_pose_kp1.pose.position.x - tf_pose_k.pose.position.x));
813 if (i < range_end - 1) tf_pose_k = tf_pose_kp1;
820 ROS_WARN_COND(opt_inscribed_radius + min_obst_dist < costmap_inscribed_radius,
821 "The inscribed radius of the footprint specified for TEB optimization (%f) + min_obstacle_dist (%f) are smaller "
822 "than the inscribed radius of the robot's footprint in the costmap parameters (%f, including 'footprint_padding'). "
823 "Infeasible optimziation results might occur frequently!",
824 opt_inscribed_radius, min_obst_dist, costmap_inscribed_radius);
835 ROS_INFO_ONCE(
"Via-points received. This message is printed once.");
839 "Via-points are already obtained from the global plan (global_plan_viapoint_sep>0)."
840 "Ignoring custom via-points.");
847 for (
const geometry_msgs::PoseStamped& pose : via_points_msg->poses)
857 std::string model_name;
858 if (!nh.
getParam(
"footprint_model/type", model_name))
860 ROS_INFO(
"No robot footprint model specified for trajectory optimization. Using point-shaped model.");
861 return boost::make_shared<teb_local_planner::PointRobotFootprint>();
865 if (model_name.compare(
"costmap_2d") == 0)
869 ROS_WARN_STREAM(
"Costmap 2d pointer is null. Using point model instead.");
870 return boost::make_shared<teb_local_planner::PointRobotFootprint>();
872 ROS_INFO(
"Footprint model loaded from costmap_2d for trajectory optimization.");
877 if (model_name.compare(
"point") == 0)
879 ROS_INFO(
"Footprint model 'point' loaded for trajectory optimization.");
880 return boost::make_shared<teb_local_planner::PointRobotFootprint>();
884 if (model_name.compare(
"circular") == 0)
888 if (!nh.
getParam(
"footprint_model/radius", radius))
890 ROS_ERROR_STREAM(
"Footprint model 'circular' cannot be loaded for trajectory optimization, since param '"
891 << nh.
getNamespace() <<
"/footprint_model/radius' does not exist. Using point-model instead.");
892 return boost::make_shared<teb_local_planner::PointRobotFootprint>();
894 ROS_INFO_STREAM(
"Footprint model 'circular' (radius: " << radius <<
"m) loaded for trajectory optimization.");
895 return boost::make_shared<teb_local_planner::CircularRobotFootprint>(radius);
899 if (model_name.compare(
"line") == 0)
902 if (!nh.
hasParam(
"footprint_model/line_start") || !nh.
hasParam(
"footprint_model/line_end"))
904 ROS_ERROR_STREAM(
"Footprint model 'line' cannot be loaded for trajectory optimization, since param '"
905 << nh.
getNamespace() <<
"/footprint_model/line_start' and/or '.../line_end' do not exist. Using point-model instead.");
906 return boost::make_shared<teb_local_planner::PointRobotFootprint>();
910 nh.
getParam(
"footprint_model/line_start", line_start);
911 nh.
getParam(
"footprint_model/line_end", line_end);
915 "Footprint model 'line' cannot be loaded for trajectory optimization, since param '"
917 <<
"/footprint_model/line_start' and/or '.../line_end' do not contain x and y coordinates (2D). Using point-model instead.");
918 return boost::make_shared<teb_local_planner::PointRobotFootprint>();
921 ROS_INFO_STREAM(
"Footprint model 'line' (line_start: [" << line_start[0] <<
"," << line_start[1] <<
"]m, line_end: [" << line_end[0] <<
","
922 << line_end[1] <<
"]m) loaded for trajectory optimization.");
928 if (model_name.compare(
"two_circles") == 0)
931 if (!nh.
hasParam(
"footprint_model/front_offset") || !nh.
hasParam(
"footprint_model/front_radius") ||
932 !nh.
hasParam(
"footprint_model/rear_offset") || !nh.
hasParam(
"footprint_model/rear_radius"))
934 ROS_ERROR_STREAM(
"Footprint model 'two_circles' cannot be loaded for trajectory optimization, since params '"
936 <<
"/footprint_model/front_offset', '.../front_radius', '.../rear_offset' and '.../rear_radius' do not exist. Using "
937 "point-model instead.");
938 return boost::make_shared<teb_local_planner::PointRobotFootprint>();
940 double front_offset, front_radius, rear_offset, rear_radius;
941 nh.
getParam(
"footprint_model/front_offset", front_offset);
942 nh.
getParam(
"footprint_model/front_radius", front_radius);
943 nh.
getParam(
"footprint_model/rear_offset", rear_offset);
944 nh.
getParam(
"footprint_model/rear_radius", rear_radius);
945 ROS_INFO_STREAM(
"Footprint model 'two_circles' (front_offset: " << front_offset <<
"m, front_radius: " << front_radius
946 <<
"m, rear_offset: " << rear_offset <<
"m, rear_radius: " << rear_radius
947 <<
"m) loaded for trajectory optimization.");
948 return boost::make_shared<teb_local_planner::TwoCirclesRobotFootprint>(front_offset, front_radius, rear_offset, rear_radius);
952 if (model_name.compare(
"polygon") == 0)
957 if (!nh.
getParam(
"footprint_model/vertices", footprint_xmlrpc))
959 ROS_ERROR_STREAM(
"Footprint model 'polygon' cannot be loaded for trajectory optimization, since param '"
960 << nh.
getNamespace() <<
"/footprint_model/vertices' does not exist. Using point-model instead.");
961 return boost::make_shared<teb_local_planner::PointRobotFootprint>();
969 ROS_INFO_STREAM(
"Footprint model 'polygon' loaded for trajectory optimization.");
970 return boost::make_shared<teb_local_planner::PolygonRobotFootprint>(polygon);
972 catch (
const std::exception& ex)
974 ROS_ERROR_STREAM(
"Footprint model 'polygon' cannot be loaded for trajectory optimization: " << ex.what()
975 <<
". Using point-model instead.");
976 return boost::make_shared<teb_local_planner::PointRobotFootprint>();
981 ROS_ERROR_STREAM(
"Footprint model 'polygon' cannot be loaded for trajectory optimization, since param '"
983 <<
"/footprint_model/vertices' does not define an array of coordinates. Using point-model instead.");
984 return boost::make_shared<teb_local_planner::PointRobotFootprint>();
990 <<
"/footprint_model/type'. Using point model instead.");
991 return boost::make_shared<teb_local_planner::PointRobotFootprint>();
1000 for (
int i = 0; i < polygon.points.size(); ++i)
1002 pt.x() = polygon.points[i].x;
1003 pt.y() = polygon.points[i].y;
1005 footprint.push_back(pt);
1007 return boost::make_shared<teb_local_planner::PolygonRobotFootprint>(footprint);
1011 const std::string& full_param_name)
1016 ROS_FATAL(
"The footprint must be specified as list of lists on the parameter server, %s was specified as %s", full_param_name.c_str(),
1017 std::string(footprint_xmlrpc).c_str());
1018 throw std::runtime_error(
1019 "The footprint must be specified as list of lists on the parameter server with at least "
1020 "3 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
1026 for (
int i = 0; i < footprint_xmlrpc.
size(); ++i)
1033 "The footprint (parameter %s) must be specified as list of lists on the parameter server eg: "
1034 "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form.",
1035 full_param_name.c_str());
1036 throw std::runtime_error(
1037 "The footprint must be specified as list of lists on the parameter server eg: "
1038 "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form");
1044 footprint.push_back(pt);
1054 std::string& value_string = value;
1055 ROS_FATAL(
"Values in the footprint specification (param %s) must be numbers. Found value %s.", full_param_name.c_str(), value_string.c_str());
1056 throw std::runtime_error(
"Values in the footprint specification must be numbers");