43 #include <boost/algorithm/string.hpp> 48 #include "g2o/core/sparse_optimizer.h" 49 #include "g2o/core/block_solver.h" 50 #include "g2o/core/factory.h" 51 #include "g2o/core/optimization_algorithm_gauss_newton.h" 52 #include "g2o/core/optimization_algorithm_levenberg.h" 53 #include "g2o/solvers/csparse/linear_solver_csparse.h" 54 #include "g2o/solvers/cholmod/linear_solver_cholmod.h" 64 TebLocalPlannerROS::TebLocalPlannerROS() : costmap_ros_(NULL),
tf_(NULL), costmap_model_(NULL),
65 costmap_converter_loader_(
"costmap_converter",
"costmap_converter::BaseCostmapToPolygons"),
66 dynamic_recfg_(NULL), custom_via_points_active_(false), goal_reached_(false), no_infeasible_plans_(0),
67 last_preferred_rotdir_(
RotType::
none), initialized_(false)
105 ROS_INFO(
"Parallel planning in distinctive topologies enabled.");
110 ROS_INFO(
"Parallel planning in distinctive topologies disabled.");
118 costmap_model_ = boost::make_shared<base_local_planner::CostmapModel>(*costmap_);
132 boost::replace_all(converter_name,
"::",
"/");
142 ROS_WARN(
"The specified costmap converter plugin cannot be loaded. All occupied costmap cells are treaten as point obstacles. Error message: %s", ex.what());
147 ROS_INFO(
"No costmap conversion plugin specified. All occupied costmap cells are treaten as point obstacles.");
158 dynamic_recfg_ = boost::make_shared< dynamic_reconfigure::Server<TebLocalPlannerReconfigureConfig> >(nh);
173 double controller_frequency = 5;
174 nh_move_base.
param(
"controller_frequency", controller_frequency, controller_frequency);
180 ROS_DEBUG(
"teb_local_planner plugin initialized.");
184 ROS_WARN(
"teb_local_planner has already been initialized, doing nothing.");
195 ROS_ERROR(
"teb_local_planner has not been initialized, please call initialize() before using this planner");
218 ROS_ERROR(
"teb_local_planner has not been initialized, please call initialize() before using this planner");
222 cmd_vel.linear.x = 0;
223 cmd_vel.linear.y = 0;
224 cmd_vel.angular.z = 0;
235 robot_vel_.linear.x = robot_vel_tf.getOrigin().getX();
236 robot_vel_.linear.y = robot_vel_tf.getOrigin().getY();
243 std::vector<geometry_msgs::PoseStamped> transformed_plan;
247 transformed_plan, &goal_idx, &tf_plan_to_global))
249 ROS_WARN(
"Could not transform the global plan to the frame of the controller");
260 global_goal.
setData( tf_plan_to_global * global_goal );
261 double dx = global_goal.getOrigin().getX() -
robot_pose_.
x();
262 double dy = global_goal.getOrigin().getY() -
robot_pose_.
y();
278 if (transformed_plan.empty())
280 ROS_WARN(
"Transformed plan is empty. Cannot determine a local plan.");
301 if (transformed_plan.size()==1)
303 transformed_plan.insert(transformed_plan.begin(), geometry_msgs::PoseStamped());
329 ROS_WARN(
"teb_local_planner was not able to obtain a local plan for the current setting.");
348 cmd_vel.linear.x = 0;
349 cmd_vel.linear.y = 0;
350 cmd_vel.angular.z = 0;
354 ROS_WARN(
"TebLocalPlannerROS: trajectory is not feasible. Resetting planner...");
366 ROS_WARN(
"TebLocalPlannerROS: velocity command invalid. Resetting planner...");
383 if (!std::isfinite(cmd_vel.angular.z))
385 cmd_vel.linear.x = cmd_vel.linear.y = cmd_vel.angular.z = 0;
388 ROS_WARN(
"TebLocalPlannerROS: Resulting steering angle is not finite. Resetting planner...");
461 for (std::size_t i=0; i<obstacles->obstacles.size(); ++i)
463 const costmap_converter::ObstacleMsg* obstacle = &obstacles->obstacles.at(i);
464 const geometry_msgs::Polygon* polygon = &obstacle->polygon;
466 if (polygon->points.size()==1 && obstacle->radius > 0)
470 else if (polygon->points.size()==1)
474 else if (polygon->points.size()==2)
477 polygon->points[1].x, polygon->points[1].y )));
479 else if (polygon->points.size()>2)
482 for (std::size_t j=0; j<polygon->points.size(); ++j)
484 polyobst->
pushBackVertex(polygon->points[j].x, polygon->points[j].y);
492 obstacles_.back()->setCentroidVelocity(obstacles->obstacles[i].velocities, obstacles->obstacles[i].orientation);
505 Eigen::Affine3d obstacle_to_map_eig;
520 obstacle_to_map_eig.setIdentity();
548 (obstacle_to_map_eig *
line_end).head(2) )));
552 ROS_WARN(
"Invalid custom obstacle received. List of polygon vertices is empty. Skipping...");
580 if (min_separation<=0)
583 std::size_t prev_idx = 0;
584 for (std::size_t i=1; i < transformed_plan.size(); ++i)
587 if (
distance_points2d( transformed_plan[prev_idx].pose.position, transformed_plan[i].pose.position ) < min_separation)
591 via_points_.push_back( Eigen::Vector2d( transformed_plan[i].pose.position.x, transformed_plan[i].pose.position.y ) );
608 if (global_plan.empty())
617 robot.
setData( global_to_plan_transform * global_pose );
619 double dist_thresh_sq = dist_behind_robot*dist_behind_robot;
622 std::vector<geometry_msgs::PoseStamped>::iterator it = global_plan.begin();
623 std::vector<geometry_msgs::PoseStamped>::iterator erase_end = it;
624 while (it != global_plan.end())
626 double dx = robot.getOrigin().x() - it->pose.position.x;
627 double dy = robot.getOrigin().y() - it->pose.position.y;
628 double dist_sq = dx * dx + dy * dy;
629 if (dist_sq < dist_thresh_sq)
636 if (erase_end == global_plan.end())
639 if (erase_end != global_plan.begin())
640 global_plan.erase(global_plan.begin(), erase_end);
644 ROS_DEBUG(
"Cannot prune path since no transform is available: %s\n", ex.what());
653 std::vector<geometry_msgs::PoseStamped>& transformed_plan,
int* current_goal_idx,
tf::StampedTransform* tf_plan_to_global)
const 657 const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
659 transformed_plan.clear();
663 if (global_plan.empty())
665 ROS_ERROR(
"Received plan with zero length");
666 *current_goal_idx = 0;
673 plan_pose.header.frame_id, plan_pose.header.stamp,
676 plan_pose.header.frame_id, plan_pose.header.stamp,
677 plan_pose.header.frame_id, plan_to_global_transform);
681 tf.
transformPose(plan_pose.header.frame_id, global_pose, robot_pose);
686 dist_threshold *= 0.85;
691 double sq_dist_threshold = dist_threshold * dist_threshold;
692 double sq_dist = 1e10;
695 for(
int j=0; j < (int)global_plan.size(); ++j)
697 double x_diff = robot_pose.getOrigin().x() - global_plan[j].pose.position.x;
698 double y_diff = robot_pose.getOrigin().y() - global_plan[j].pose.position.y;
699 double new_sq_dist = x_diff * x_diff + y_diff * y_diff;
700 if (new_sq_dist > sq_dist_threshold)
703 if (new_sq_dist < sq_dist)
705 sq_dist = new_sq_dist;
711 geometry_msgs::PoseStamped newer_pose;
713 double plan_length = 0;
716 while(i < (
int)global_plan.size() && sq_dist <= sq_dist_threshold && (max_plan_length<=0 || plan_length <= max_plan_length))
718 const geometry_msgs::PoseStamped& pose = global_plan[i];
720 tf_pose.
setData(plan_to_global_transform * tf_pose);
721 tf_pose.stamp_ = plan_to_global_transform.
stamp_;
722 tf_pose.frame_id_ = global_frame;
725 transformed_plan.push_back(newer_pose);
727 double x_diff = robot_pose.getOrigin().x() - global_plan[i].pose.position.x;
728 double y_diff = robot_pose.getOrigin().y() - global_plan[i].pose.position.y;
729 sq_dist = x_diff * x_diff + y_diff * y_diff;
732 if (i>0 && max_plan_length>0)
733 plan_length +=
distance_points2d(global_plan[i-1].pose.position, global_plan[i].pose.position);
740 if (transformed_plan.empty())
743 tf_pose.
setData(plan_to_global_transform * tf_pose);
744 tf_pose.stamp_ = plan_to_global_transform.
stamp_;
745 tf_pose.frame_id_ = global_frame;
748 transformed_plan.push_back(newer_pose);
751 if (current_goal_idx) *current_goal_idx = int(global_plan.size())-1;
756 if (current_goal_idx) *current_goal_idx = i-1;
760 if (tf_plan_to_global) *tf_plan_to_global = plan_to_global_transform;
764 ROS_ERROR(
"No Transform available Error: %s\n", ex.what());
769 ROS_ERROR(
"Connectivity Error: %s\n", ex.what());
774 ROS_ERROR(
"Extrapolation Error: %s\n", ex.what());
775 if (global_plan.size() > 0)
776 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());
788 int current_goal_idx,
const tf::StampedTransform& tf_plan_to_global,
int moving_average_length)
const 790 int n = (int)global_plan.size();
793 if (current_goal_idx > n-moving_average_length-2)
795 if (current_goal_idx >= n-1)
808 moving_average_length = std::min(moving_average_length, n-current_goal_idx-1 );
810 std::vector<double> candidates;
814 int range_end = current_goal_idx + moving_average_length;
815 for (
int i = current_goal_idx; i < range_end; ++i)
818 const geometry_msgs::PoseStamped& pose = global_plan.at(i+1);
820 tf_pose_kp1.
setData(tf_plan_to_global * tf_pose_kp1);
823 candidates.push_back( std::atan2(tf_pose_kp1.getOrigin().getY() - tf_pose_k.getOrigin().getY(),
824 tf_pose_kp1.getOrigin().getX() - tf_pose_k.getOrigin().getX() ) );
827 tf_pose_k = tf_pose_kp1;
842 else if (vy < -max_vel_y)
846 if (omega > max_vel_theta)
847 omega = max_vel_theta;
848 else if (omega < -max_vel_theta)
849 omega = -max_vel_theta;
852 if (max_vel_x_backwards<=0)
854 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.");
856 else if (vx < -max_vel_x_backwards)
857 vx = -max_vel_x_backwards;
863 if (omega==0 || v==0)
866 double radius = v/omega;
868 if (fabs(radius) < min_turning_radius)
869 radius = double(
g2o::sign(radius)) * min_turning_radius;
871 return std::atan(wheelbase / radius);
877 ROS_WARN_COND(opt_inscribed_radius + min_obst_dist < costmap_inscribed_radius,
878 "The inscribed radius of the footprint specified for TEB optimization (%f) + min_obstacle_dist (%f) are smaller " 879 "than the inscribed radius of the robot's footprint in the costmap parameters (%f, including 'footprint_padding'). " 880 "Infeasible optimziation results might occur frequently!", opt_inscribed_radius, min_obst_dist, costmap_inscribed_radius);
891 goal_idx < (
int)transformed_plan.size()-1 &&
899 int horizon_reduction = goal_idx/2;
904 horizon_reduction /= 2;
910 int new_goal_idx_transformed_plan = int(transformed_plan.size()) - horizon_reduction - 1;
911 goal_idx -= horizon_reduction;
912 if (new_goal_idx_transformed_plan>0 && goal_idx >= 0)
913 transformed_plan.erase(transformed_plan.begin()+new_goal_idx_transformed_plan, transformed_plan.end());
915 goal_idx += horizon_reduction;
922 double max_vel_theta;
937 if (!recently_oscillated)
944 ROS_WARN(
"TebLocalPlannerROS: possible oscillation (of the robot or its local plan) detected. Activating recovery strategy (prefer current turning direction during optimization).");
953 ROS_INFO(
"TebLocalPlannerROS: oscillation recovery disabled/expired.");
968 ROS_INFO_ONCE(
"Via-points received. This message is printed once.");
971 ROS_WARN(
"Via-points are already obtained from the global plan (global_plan_viapoint_sep>0)." 972 "Ignoring custom via-points.");
979 for (
const geometry_msgs::PoseStamped& pose : via_points_msg->poses)
981 via_points_.emplace_back(pose.pose.position.x, pose.pose.position.y);
988 std::string model_name;
989 if (!nh.
getParam(
"footprint_model/type", model_name))
991 ROS_INFO(
"No robot footprint model specified for trajectory optimization. Using point-shaped model.");
992 return boost::make_shared<PointRobotFootprint>();
996 if (model_name.compare(
"point") == 0)
998 ROS_INFO(
"Footprint model 'point' loaded for trajectory optimization.");
999 return boost::make_shared<PointRobotFootprint>();
1003 if (model_name.compare(
"circular") == 0)
1007 if (!nh.
getParam(
"footprint_model/radius", radius))
1010 <<
"/footprint_model/radius' does not exist. Using point-model instead.");
1011 return boost::make_shared<PointRobotFootprint>();
1013 ROS_INFO_STREAM(
"Footprint model 'circular' (radius: " << radius <<
"m) loaded for trajectory optimization.");
1014 return boost::make_shared<CircularRobotFootprint>(radius);
1018 if (model_name.compare(
"line") == 0)
1021 if (!nh.
hasParam(
"footprint_model/line_start") || !nh.
hasParam(
"footprint_model/line_end"))
1024 <<
"/footprint_model/line_start' and/or '.../line_end' do not exist. Using point-model instead.");
1025 return boost::make_shared<PointRobotFootprint>();
1029 nh.
getParam(
"footprint_model/line_start", line_start);
1030 nh.
getParam(
"footprint_model/line_end", line_end);
1031 if (line_start.size() != 2 || line_end.size() != 2)
1034 <<
"/footprint_model/line_start' and/or '.../line_end' do not contain x and y coordinates (2D). Using point-model instead.");
1035 return boost::make_shared<PointRobotFootprint>();
1038 ROS_INFO_STREAM(
"Footprint model 'line' (line_start: [" << line_start[0] <<
"," << line_start[1] <<
"]m, line_end: [" 1039 << line_end[0] <<
"," << line_end[1] <<
"]m) loaded for trajectory optimization.");
1040 return boost::make_shared<LineRobotFootprint>(Eigen::Map<const Eigen::Vector2d>(line_start.data()), Eigen::Map<const Eigen::Vector2d>(line_end.data()));
1044 if (model_name.compare(
"two_circles") == 0)
1047 if (!nh.
hasParam(
"footprint_model/front_offset") || !nh.
hasParam(
"footprint_model/front_radius")
1048 || !nh.
hasParam(
"footprint_model/rear_offset") || !nh.
hasParam(
"footprint_model/rear_radius"))
1051 <<
"/footprint_model/front_offset', '.../front_radius', '.../rear_offset' and '.../rear_radius' do not exist. Using point-model instead.");
1052 return boost::make_shared<PointRobotFootprint>();
1054 double front_offset, front_radius, rear_offset, rear_radius;
1055 nh.
getParam(
"footprint_model/front_offset", front_offset);
1056 nh.
getParam(
"footprint_model/front_radius", front_radius);
1057 nh.
getParam(
"footprint_model/rear_offset", rear_offset);
1058 nh.
getParam(
"footprint_model/rear_radius", rear_radius);
1059 ROS_INFO_STREAM(
"Footprint model 'two_circles' (front_offset: " << front_offset <<
"m, front_radius: " << front_radius
1060 <<
"m, rear_offset: " << rear_offset <<
"m, rear_radius: " << rear_radius <<
"m) loaded for trajectory optimization.");
1061 return boost::make_shared<TwoCirclesRobotFootprint>(front_offset, front_radius, rear_offset, rear_radius);
1065 if (model_name.compare(
"polygon") == 0)
1070 if (!nh.
getParam(
"footprint_model/vertices", footprint_xmlrpc) )
1073 <<
"/footprint_model/vertices' does not exist. Using point-model instead.");
1074 return boost::make_shared<PointRobotFootprint>();
1082 ROS_INFO_STREAM(
"Footprint model 'polygon' loaded for trajectory optimization.");
1083 return boost::make_shared<PolygonRobotFootprint>(polygon);
1085 catch(
const std::exception& ex)
1087 ROS_ERROR_STREAM(
"Footprint model 'polygon' cannot be loaded for trajectory optimization: " << ex.what() <<
". Using point-model instead.");
1088 return boost::make_shared<PointRobotFootprint>();
1094 <<
"/footprint_model/vertices' does not define an array of coordinates. Using point-model instead.");
1095 return boost::make_shared<PointRobotFootprint>();
1101 ROS_WARN_STREAM(
"Unknown robot footprint model specified with parameter '" << nh.
getNamespace() <<
"/footprint_model/type'. Using point model instead.");
1102 return boost::make_shared<PointRobotFootprint>();
1112 footprint_xmlrpc.
size() < 3)
1114 ROS_FATAL(
"The footprint must be specified as list of lists on the parameter server, %s was specified as %s",
1115 full_param_name.c_str(), std::string(footprint_xmlrpc).c_str());
1116 throw std::runtime_error(
"The footprint must be specified as list of lists on the parameter server with at least " 1117 "3 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
1123 for (
int i = 0; i < footprint_xmlrpc.
size(); ++i)
1130 ROS_FATAL(
"The footprint (parameter %s) must be specified as list of lists on the parameter server eg: " 1131 "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form.",
1132 full_param_name.c_str());
1133 throw std::runtime_error(
"The footprint must be specified as list of lists on the parameter server eg: " 1134 "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form");
1140 footprint.push_back(pt);
1151 std::string& value_string = value;
1152 ROS_FATAL(
"Values in the footprint specification (param %s) must be numbers. Found value %s.",
1153 full_param_name.c_str(), value_string.c_str());
1154 throw std::runtime_error(
"Values in the footprint specification must be numbers");
bool include_costmap_obstacles
Specify whether the obstacles in the costmap should be taken into account directly.
bool cmd_angle_instead_rotvel
Substitute the rotational velocity in the commanded velocity message by the corresponding steering an...
boost::shared_ptr< PlannerInterface > PlannerInterfacePtr
Abbrev. for shared instances of PlannerInterface or it's subclasses.
Implements a 2D circular obstacle (point obstacle plus radius)
boost::shared_ptr< dynamic_reconfigure::Server< TebLocalPlannerReconfigureConfig > > dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
bool isGoalReached()
Check if the goal pose has been achieved.
std::string map_frame
Global planning frame.
TebVisualizationPtr visualization_
Instance of the visualization class (local/global plan, obstacles, ...)
double max_vel_y
Maximum strafing velocity of the robot (should be zero for non-holonomic robots!) ...
void finalizePolygon()
Call finalizePolygon after the polygon is created with the help of pushBackVertex() methods...
boost::mutex via_point_mutex_
Mutex that locks the via_points container (multi-threaded)
costmap_converter::ObstacleArrayMsg custom_obstacle_msg_
Copy of the most recent obstacle message.
PoseSE2 robot_goal_
Store current robot goal.
void getRobotVel(tf::Stamped< tf::Pose > &robot_vel)
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the teb plugin.
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
bool initialized_
Keeps track about the correct initialization of this class.
double min_obstacle_dist
Minimum desired separation from obstacles.
void setData(const T &input)
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
bool shrink_horizon_backup
Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues...
#define ROS_INFO_ONCE(...)
Eigen::Vector2d & position()
Access the 2D position part.
double robot_circumscribed_radius
The radius of the circumscribed circle of the robot.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void updateViaPointsContainer(const std::vector< geometry_msgs::PoseStamped > &transformed_plan, double min_separation)
Update internal via-point container based on the current reference plan.
bool pruneGlobalPlan(const tf::TransformListener &tf, const tf::Stamped< tf::Pose > &global_pose, std::vector< geometry_msgs::PoseStamped > &global_plan, double dist_behind_robot=1)
Prune global plan such that already passed poses are cut off.
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
boost::shared_ptr< base_local_planner::CostmapModel > costmap_model_
static double getYaw(const Quaternion &bt_q)
bool custom_via_points_active_
Keep track whether valid via-points have been received from via_points_sub_.
double xy_goal_tolerance
Allowed final euclidean distance to the goal position.
double global_plan_viapoint_sep
Min. separation between each two consecutive via-points extracted from the global plan (if negative: ...
void customViaPointsCB(const nav_msgs::Path::ConstPtr &via_points_msg)
Callback for custom via-points.
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons > costmap_converter_loader_
Load costmap converter plugins at runtime.
bool transformGlobalPlan(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const tf::Stamped< tf::Pose > &global_pose, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, double max_plan_length, std::vector< geometry_msgs::PoseStamped > &transformed_plan, int *current_goal_idx=NULL, tf::StampedTransform *tf_plan_to_global=NULL) const
Transforms the global plan of the robot from the planner frame to the local frame (modified)...
std::string getGlobalFrameID()
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
std::vector< geometry_msgs::Point > footprint_spec_
Store the footprint of the robot.
int no_infeasible_plans_
Store how many times in a row the planner failed to find a feasible plan.
Local planner that explores alternative homotopy classes, create a plan for each alternative and fina...
double yaw_goal_tolerance
Allowed final orientation error.
double min_turning_radius
Minimum turning radius of a carlike robot (diff-drive robot: zero);.
static RobotFootprintModelPtr getRobotFootprintFromParamServer(const ros::NodeHandle &nh)
Get the current robot footprint/contour model.
FailureDetector failure_detector_
Detect if the robot got stucked.
TFSIMD_FORCE_INLINE const tfScalar & getY() const
bool goal_reached_
store whether the goal is reached or not
double & x()
Access the x-coordinate the pose.
void setBufferLength(int length)
Set buffer length (measurement history)
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
ros::Time time_last_infeasible_plan_
Store at which time stamp the last infeasible plan was detected.
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
Type const & getType() const
void updateObstacleContainerWithCostmapConverter()
Update internal obstacle vector based on polygons provided by a costmap_converter plugin...
ros::Subscriber custom_obst_sub_
Subscriber for custom obstacles received via a ObstacleMsg.
Implements a polygon obstacle with an arbitrary number of vertices.
Implements a 2D line obstacle.
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
int feasibility_check_no_poses
Specify up to which pose on the predicted plan the feasibility should be checked each sampling interv...
double costmap_obstacles_behind_robot_dist
Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify ...
struct teb_local_planner::TebConfig::GoalTolerance goal_tolerance
Goal tolerance related parameters.
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
boost::mutex custom_obst_mutex_
Mutex that locks the obstacle array (multi-threaded)
boost::shared_ptr< Obstacle > ObstaclePtr
Abbrev. for shared obstacle pointers.
std::vector< geometry_msgs::PoseStamped > global_plan_
Store the current global plan.
void update(const geometry_msgs::Twist &twist, double v_max, double v_backwards_max, double omega_max, double v_eps, double omega_eps)
Add a new twist measurement to the internal buffer and compute a new decision.
void reconfigure(TebLocalPlannerReconfigureConfig &cfg)
Reconfigure parameters from the dynamic_reconfigure config. Change parameters dynamically (e...
unsigned char getCost(unsigned int mx, unsigned int my) const
void updateObstacleContainerWithCustomObstacles()
Update internal obstacle vector based on custom messages received via subscriber. ...
RotType
Symbols for left/none/right rotations.
costmap_2d::Costmap2DROS * costmap_ros_
Pointer to the costmap ros wrapper, received from the navigation stack.
tf::TransformListener * tf_
pointer to Transform Listener
void loadRosParamFromNodeHandle(const ros::NodeHandle &nh)
Load parmeters from the ros param server.
RotType last_preferred_rotdir_
Store recent preferred turning direction.
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
#define ROS_WARN_ONCE(...)
struct teb_local_planner::TebConfig::HomotopyClasses hcp
std::string odom_topic
Topic name of the odometry message, provided by the robot driver or simulator.
~TebLocalPlannerROS()
Destructor of the plugin.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
double estimateLocalGoalOrientation(const std::vector< geometry_msgs::PoseStamped > &global_plan, const tf::Stamped< tf::Pose > &local_goal, int current_goal_idx, const tf::StampedTransform &tf_plan_to_global, int moving_average_length=3) const
Estimate the orientation of a pose from the global_plan that is treated as a local goal for the local...
Implements a 2D point obstacle.
int control_look_ahead_poses
Min angular resolution used during the costmap collision check. If not respected, intermediate sample...
std::string getBaseFrameID()
const std::string & getNamespace() const
TebConfig cfg_
Config class that stores and manages all related parameters.
static Point2dContainer makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue &footprint_xmlrpc, const std::string &full_param_name)
Set the footprint from the given XmlRpcValue.
bool enable_homotopy_class_planning
Activate homotopy class planning (Requires much more resources that simple planning, since multiple trajectories are optimized at once).
geometry_msgs::Twist last_cmd_
Store the last control command generated in computeVelocityCommands()
bool free_goal_vel
Allow the robot's velocity to be nonzero (usally max_vel) for planning purposes.
void pushBackVertex(const Eigen::Ref< const Eigen::Vector2d > &vertex)
Add a vertex to the polygon (edge-point)
double max_vel_theta
Maximum angular velocity of the robot.
static Eigen::Vector2d tfPoseToEigenVector2dTransRot(const tf::Pose &tf_vel)
Transform a tf::Pose type into a Eigen::Vector2d containing the translational and angular velocities...
double oscillation_v_eps
Threshold for the average normalized linear velocity: if oscillation_v_eps and oscillation_omega_eps ...
unsigned int getSizeInCellsY() const
static double getNumberFromXMLRPC(XmlRpc::XmlRpcValue &value, const std::string &full_param_name)
Get a number from the given XmlRpcValue.
#define ROS_WARN_STREAM(args)
virtual std::string getName(const std::string &lookup_name)
double oscillation_filter_duration
Filter length/duration [sec] for the detection of oscillations.
double & y()
Access the y-coordinate the pose.
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
double & theta()
Access the orientation part (yaw angle) of the pose.
void configureBackupModes(std::vector< geometry_msgs::PoseStamped > &transformed_plan, int &goal_idx)
PoseSE2 robot_pose_
Store current robot pose.
bool is_footprint_dynamic
base_local_planner::OdometryHelperRos odom_helper_
Provides an interface to receive the current velocity from the robot.
void saturateVelocity(double &vx, double &vy, double &omega, double max_vel_x, double max_vel_y, double max_vel_theta, double max_vel_x_backwards) const
Saturate the translational and angular velocity to given limits.
double shrink_horizon_min_duration
Specify minimum duration for the reduced horizon in case an infeasible trajectory is detected...
costmap_2d::Costmap2D * costmap_
Pointer to the 2d costmap (obtained from the costmap ros wrapper)
Implements the actual abstract navigation stack routines of the teb_local_planner plugin...
bool costmap_converter_spin_thread
If true, the costmap converter invokes its callback queue in a different thread.
unsigned int getSizeInCellsX() const
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
#define ROS_INFO_STREAM(args)
void customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr &obst_msg)
Callback for custom obstacles that are not obtained from the costmap.
static const unsigned char LETHAL_OBSTACLE
std::string robot_base_frame_
Used as the base frame id of the robot.
double average_angles(const std::vector< double > &angles)
Return the average angle of an arbitrary number of given angles [rad].
std::string costmap_converter_plugin
Define a plugin name of the costmap_converter package (costmap cells are converted to points/lines/po...
bool getParam(const std::string &key, std::string &s) const
bool isOscillating() const
Check if the robot got stucked.
void validateFootprints(double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist)
Validate current parameter values of the footprint for optimization, obstacle distance and the costma...
ros::Subscriber via_points_sub_
Subscriber for custom via-points received via a Path msg.
void updateObstacleContainerWithCostmap()
Update internal obstacle vector based on occupied costmap cells.
#define ROS_WARN_COND(cond,...)
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
#define ROS_INFO_COND(cond,...)
bool global_plan_overwrite_orientation
Overwrite orientation of local subgoals provided by the global planner.
struct teb_local_planner::TebConfig::Recovery recovery
Parameters related to recovery and backup strategies.
TFSIMD_FORCE_INLINE const tfScalar & getX() const
double robot_inscribed_radius_
The radius of the inscribed circle of the robot (collision possible)
boost::shared_ptr< costmap_converter::BaseCostmapToPolygons > costmap_converter_
Store the current costmap_converter.
int costmap_converter_rate
The rate that defines how often the costmap_converter plugin processes the current costmap (the value...
void setOdomTopic(std::string odom_topic)
double global_plan_prune_distance
Distance between robot and via_points of global plan which is used for pruning.
PlannerInterfacePtr planner_
Instance of the underlying optimal planner class.
static void poseStampedMsgToTF(const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
double max_vel_x_backwards
Maximum translational velocity of the robot for driving backwards.
std::string global_frame_
The frame in which the controller will run.
double oscillation_recovery_min_duration
Minumum duration [sec] for which the recovery mode is activated after an oscillation is detected...
double convertTransRotVelToSteeringAngle(double v, double omega, double wheelbase, double min_turning_radius=0) const
Convert translational and rotational velocities to a steering angle of a carlike robot.
bool complete_global_plan
ros::Time time_last_oscillation_
Store at which time stamp the last oscillation was detected.
double getResolution() const
bool hasParam(const std::string &key) const
ObstContainer obstacles_
Obstacle vector that should be considered during local trajectory optimization.
#define ROS_ERROR_STREAM(args)
double distance_points2d(const P1 &point1, const P2 &point2)
Calculate Euclidean distance between two 2D point datatypes.
std::vector< geometry_msgs::Point > getRobotFootprint()
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the teb local planner is following.
ViaPointContainer via_points_
Container of via-points that should be considered during local trajectory optimization.
double oscillation_omega_eps
Threshold for the average normalized angular velocity: if oscillation_v_eps and oscillation_omega_eps...
double wheelbase
The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_a...
double max_global_plan_lookahead_dist
Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into a...
geometry_msgs::Twist robot_vel_
Store current robot translational and angular velocity (vx, vy, omega)
bool oscillation_recovery
Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robo...
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
boost::mutex & configMutex()
Return the internal config mutex.
double max_vel_x
Maximum translational velocity of the robot.
void reconfigureCB(TebLocalPlannerReconfigureConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
void calculateMinAndMaxDistances(const std::vector< geometry_msgs::Point > &footprint, double &min_dist, double &max_dist)