teb_local_planner_ros.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Christoph Rösmann
37  *********************************************************************/
38 
39 #ifndef TEB_LOCAL_PLANNER_ROS_H_
40 #define TEB_LOCAL_PLANNER_ROS_H_
41 
42 #include <ros/ros.h>
43 
44 // base local planner base class and utilities
50 
51 
52 // timed-elastic-band related classes
57 
58 // message types
59 #include <nav_msgs/Path.h>
60 #include <nav_msgs/Odometry.h>
61 #include <geometry_msgs/PoseStamped.h>
62 #include <visualization_msgs/MarkerArray.h>
63 #include <visualization_msgs/Marker.h>
64 #include <costmap_converter/ObstacleMsg.h>
65 
66 // transforms
67 #include <tf2/utils.h>
68 #include <tf2_ros/buffer.h>
69 
70 // costmap
73 
74 
75 // dynamic reconfigure
76 #include <teb_local_planner/TebLocalPlannerReconfigureConfig.h>
77 #include <dynamic_reconfigure/server.h>
78 
79 // boost classes
80 #include <boost/bind.hpp>
81 #include <boost/shared_ptr.hpp>
82 
83 
84 namespace teb_local_planner
85 {
86 
93 class TebLocalPlannerROS : public nav_core::BaseLocalPlanner, public mbf_costmap_core::CostmapController
94 {
95 
96 public:
101 
106 
113  void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS* costmap_ros);
114 
120  bool setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
121 
128 
156  uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped& pose, const geometry_msgs::TwistStamped& velocity,
157  geometry_msgs::TwistStamped &cmd_vel, std::string &message);
158 
166  bool isGoalReached();
167 
171  bool isGoalReached(double xy_tolerance, double yaw_tolerance) { return isGoalReached(); };
172 
178  bool cancel() { return false; };
179 
180 
183 
191  static Eigen::Vector2d tfPoseToEigenVector2dTransRot(const tf::Pose& tf_vel);
192 
200 
211  static Point2dContainer makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc, const std::string& full_param_name);
212 
222  static double getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value, const std::string& full_param_name);
223 
225 
226 protected:
227 
237 
245 
252 
253 
260  void updateViaPointsContainer(const std::vector<geometry_msgs::PoseStamped>& transformed_plan, double min_separation);
261 
262 
270  void reconfigureCB(TebLocalPlannerReconfigureConfig& config, uint32_t level);
271 
272 
277  void customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg);
278 
283  void customViaPointsCB(const nav_msgs::Path::ConstPtr& via_points_msg);
284 
300  bool pruneGlobalPlan(const tf2_ros::Buffer& tf, const geometry_msgs::PoseStamped& global_pose,
301  std::vector<geometry_msgs::PoseStamped>& global_plan, double dist_behind_robot=1);
302 
320  bool transformGlobalPlan(const tf2_ros::Buffer& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
321  const geometry_msgs::PoseStamped& global_pose, const costmap_2d::Costmap2D& costmap,
322  const std::string& global_frame, double max_plan_length, std::vector<geometry_msgs::PoseStamped>& transformed_plan,
323  int* current_goal_idx = NULL, geometry_msgs::TransformStamped* tf_plan_to_global = NULL) const;
324 
340  double estimateLocalGoalOrientation(const std::vector<geometry_msgs::PoseStamped>& global_plan, const geometry_msgs::PoseStamped& local_goal,
341  int current_goal_idx, const geometry_msgs::TransformStamped& tf_plan_to_global, int moving_average_length=3) const;
342 
343 
359  void saturateVelocity(double& vx, double& vy, double& omega, double max_vel_x, double max_vel_y,
360  double max_vel_trans, double max_vel_theta, double max_vel_x_backwards) const;
361 
362 
377  double convertTransRotVelToSteeringAngle(double v, double omega, double wheelbase, double min_turning_radius = 0) const;
378 
388  void validateFootprints(double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist);
389 
390 
391  void configureBackupModes(std::vector<geometry_msgs::PoseStamped>& transformed_plan, int& goal_idx);
392 
393 
394 
395 private:
396  // Definition of member variables
397 
398  // external objects (store weak pointers)
402 
403  // internal objects (memory management owned)
409  TebConfig cfg_;
410  FailureDetector failure_detector_;
411 
412  std::vector<geometry_msgs::PoseStamped> global_plan_;
413 
415 
418 
421  boost::mutex custom_obst_mutex_;
422  costmap_converter::ObstacleArrayMsg custom_obstacle_msg_;
423 
426  boost::mutex via_point_mutex_;
427 
428  PoseSE2 robot_pose_;
429  PoseSE2 robot_goal_;
431  bool goal_reached_;
437 
438  std::vector<geometry_msgs::Point> footprint_spec_;
439  double robot_inscribed_radius_;
441 
442  std::string global_frame_;
443  std::string robot_base_frame_;
444  std::string name_;
445 
446  // flags
447  bool initialized_;
448 
449 public:
450  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
451 };
452 
453 }; // end namespace teb_local_planner
454 
455 #endif // TEB_LOCAL_PLANNER_ROS_H_
456 
457 
mbf_costmap_core::CostmapController
teb_local_planner::TebLocalPlannerROS::updateObstacleContainerWithCostmap
void updateObstacleContainerWithCostmap()
Update internal obstacle vector based on occupied costmap cells.
Definition: teb_local_planner_ros.cpp:514
teb_local_planner::TebLocalPlannerROS::custom_via_points_active_
bool custom_via_points_active_
Keep track whether valid via-points have been received from via_points_sub_.
Definition: teb_local_planner_ros.h:461
teb_local_planner::TebLocalPlannerROS::computeVelocityCommands
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
Definition: teb_local_planner_ros.cpp:262
teb_local_planner::TebLocalPlannerROS::updateViaPointsContainer
void updateViaPointsContainer(const std::vector< geometry_msgs::PoseStamped > &transformed_plan, double min_separation)
Update internal via-point container based on the current reference plan.
Definition: teb_local_planner_ros.cpp:663
teb_local_planner::TebLocalPlannerROS::via_points_
ViaPointContainer via_points_
Container of via-points that should be considered during local trajectory optimization.
Definition: teb_local_planner_ros.h:442
teb_local_planner::RobotFootprintModelPtr
boost::shared_ptr< BaseRobotFootprintModel > RobotFootprintModelPtr
Abbrev. for shared obstacle pointers.
Definition: robot_footprint_model.h:156
cmd_vel_to_ackermann_drive.Twist
Twist
Definition: cmd_vel_to_ackermann_drive.py:56
teb_local_planner::TebLocalPlannerROS::custom_obstacle_msg_
costmap_converter::ObstacleArrayMsg custom_obstacle_msg_
Copy of the most recent obstacle message.
Definition: teb_local_planner_ros.h:458
teb_local_planner::TebLocalPlannerROS::robot_pose_
PoseSE2 robot_pose_
Store current robot pose.
Definition: teb_local_planner_ros.h:464
teb_local_planner::TebLocalPlannerROS::updateObstacleContainerWithCostmapConverter
void updateObstacleContainerWithCostmapConverter()
Update internal obstacle vector based on polygons provided by a costmap_converter plugin.
Definition: teb_local_planner_ros.cpp:542
boost::shared_ptr< base_local_planner::CostmapModel >
teb_local_planner::TebLocalPlannerROS::odom_helper_
base_local_planner::OdometryHelperRos odom_helper_
Provides an interface to receive the current velocity from the robot.
Definition: teb_local_planner_ros.h:450
teb_local_planner::TebLocalPlannerROS::costmap_converter_loader_
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons > costmap_converter_loader_
Load costmap converter plugins at runtime.
Definition: teb_local_planner_ros.h:452
teb_local_planner::TebLocalPlannerROS::costmap_ros_
costmap_2d::Costmap2DROS * costmap_ros_
Pointer to the costmap ros wrapper, received from the navigation stack.
Definition: teb_local_planner_ros.h:435
teb_local_planner::TebLocalPlannerROS::validateFootprints
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...
Definition: teb_local_planner_ros.cpp:972
utils.h
teb_local_planner::TebLocalPlannerROS::robot_goal_
PoseSE2 robot_goal_
Store current robot goal.
Definition: teb_local_planner_ros.h:465
ros.h
teb_local_planner::TebLocalPlannerROS::robot_vel_
geometry_msgs::Twist robot_vel_
Store current robot translational and angular velocity (vx, vy, omega)
Definition: teb_local_planner_ros.h:466
teb_local_planner::TebLocalPlannerROS::initialize
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the teb plugin.
Definition: teb_local_planner_ros.cpp:129
teb_local_planner::TebLocalPlannerROS::robot_inscribed_radius_
double robot_inscribed_radius_
The radius of the inscribed circle of the robot (collision possible)
Definition: teb_local_planner_ros.h:475
teb_local_planner::TebLocalPlannerROS::~TebLocalPlannerROS
~TebLocalPlannerROS()
Destructor of the plugin.
Definition: teb_local_planner_ros.cpp:113
teb_local_planner::TebLocalPlannerROS::time_last_infeasible_plan_
ros::Time time_last_infeasible_plan_
Store at which time stamp the last infeasible plan was detected.
Definition: teb_local_planner_ros.h:468
teb_local_planner::Point2dContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
Definition: distance_calculations.h:86
goal_functions.h
teb_local_planner::TebLocalPlannerROS::custom_obst_mutex_
boost::mutex custom_obst_mutex_
Mutex that locks the obstacle array (multi-threaded)
Definition: teb_local_planner_ros.h:457
recovery_behaviors.h
teb_local_planner::TebLocalPlannerROS::via_points_sub_
ros::Subscriber via_points_sub_
Subscriber for custom via-points received via a Path msg.
Definition: teb_local_planner_ros.h:460
teb_local_planner::TebLocalPlannerROS::costmap_
costmap_2d::Costmap2D * costmap_
Pointer to the 2d costmap (obtained from the costmap ros wrapper)
Definition: teb_local_planner_ros.h:436
cmd_vel_to_ackermann_drive.wheelbase
wheelbase
Definition: cmd_vel_to_ackermann_drive.py:52
buffer.h
costmap_2d::Costmap2D
teb_local_planner::TebLocalPlannerROS::planner_
PlannerInterfacePtr planner_
Instance of the underlying optimal planner class.
Definition: teb_local_planner_ros.h:440
costmap_2d_ros.h
teb_local_planner::TebLocalPlannerROS::global_frame_
std::string global_frame_
The frame in which the controller will run.
Definition: teb_local_planner_ros.h:478
teb_local_planner::RotType
RotType
Symbols for left/none/right rotations
Definition: misc.h:89
teb_local_planner::TebLocalPlannerROS::TebLocalPlannerROS
TebLocalPlannerROS()
Default constructor of the teb plugin.
Definition: teb_local_planner_ros.cpp:105
config
TebConfig config
Definition: test_optim_node.cpp:56
teb_local_planner::TebLocalPlannerROS::estimateLocalGoalOrientation
double estimateLocalGoalOrientation(const std::vector< geometry_msgs::PoseStamped > &global_plan, const geometry_msgs::PoseStamped &local_goal, int current_goal_idx, const geometry_msgs::TransformStamped &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...
Definition: teb_local_planner_ros.cpp:863
teb_local_planner::TebLocalPlannerROS::tfPoseToEigenVector2dTransRot
static Eigen::Vector2d tfPoseToEigenVector2dTransRot(const tf::Pose &tf_vel)
Transform a tf::Pose type into a Eigen::Vector2d containing the translational and angular velocities.
Definition: teb_local_planner_ros.cpp:684
teb_local_planner::TebLocalPlannerROS::name_
std::string name_
For use with the ros nodehandle.
Definition: teb_local_planner_ros.h:480
base_local_planner.h
teb_local_planner::TebLocalPlannerROS::visualization_
TebVisualizationPtr visualization_
Instance of the visualization class (local/global plan, obstacles, ...)
Definition: teb_local_planner_ros.h:443
teb_local_planner::TebLocalPlannerROS::makeFootprintFromXMLRPC
static Point2dContainer makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue &footprint_xmlrpc, const std::string &full_param_name)
Set the footprint from the given XmlRpcValue.
Definition: teb_local_planner_ros.cpp:1204
teb_local_planner::TebLocalPlannerROS::robot_base_frame_
std::string robot_base_frame_
Used as the base frame id of the robot.
Definition: teb_local_planner_ros.h:479
teb_local_planner::TebLocalPlannerROS::cfg_
TebConfig cfg_
Config class that stores and manages all related parameters.
Definition: teb_local_planner_ros.h:445
teb_local_planner::TebLocalPlannerROS::customObstacleCB
void customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr &obst_msg)
Callback for custom obstacles that are not obtained from the costmap.
Definition: teb_local_planner_ros.cpp:1056
costmap_model.h
teb_local_planner::TebLocalPlannerROS::dynamic_recfg_
boost::shared_ptr< dynamic_reconfigure::Server< TebLocalPlannerReconfigureConfig > > dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
Definition: teb_local_planner_ros.h:455
teb_local_planner::ObstContainer
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
Definition: obstacles.h:333
teb_local_planner::TebLocalPlannerROS::getRobotFootprintFromParamServer
static RobotFootprintModelPtr getRobotFootprintFromParamServer(const ros::NodeHandle &nh, const TebConfig &config)
Get the current robot footprint/contour model.
Definition: teb_local_planner_ros.cpp:1082
teb_local_planner::TebLocalPlannerROS::convertTransRotVelToSteeringAngle
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.
Definition: teb_local_planner_ros.cpp:958
base_local_planner::OdometryHelperRos
teb_local_planner::TebLocalPlannerROS::time_last_oscillation_
ros::Time time_last_oscillation_
Store at which time stamp the last oscillation was detected.
Definition: teb_local_planner_ros.h:470
homotopy_class_planner.h
tf2_ros::Buffer
teb_local_planner::TebLocalPlannerROS::no_infeasible_plans_
int no_infeasible_plans_
Store how many times in a row the planner failed to find a feasible plan.
Definition: teb_local_planner_ros.h:469
teb_local_planner::TebVisualizationPtr
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
Definition: visualization.h:311
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons >
tf::Transform
teb_local_planner::TebLocalPlannerROS::transformGlobalPlan
bool transformGlobalPlan(const tf2_ros::Buffer &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const geometry_msgs::PoseStamped &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, geometry_msgs::TransformStamped *tf_plan_to_global=NULL) const
Transforms the global plan of the robot from the planner frame to the local frame (modified).
Definition: teb_local_planner_ros.cpp:737
teb_local_planner::TebLocalPlannerROS::via_point_mutex_
boost::mutex via_point_mutex_
Mutex that locks the via_points container (multi-threaded)
Definition: teb_local_planner_ros.h:462
teb_local_planner::TebLocalPlannerROS::customViaPointsCB
void customViaPointsCB(const nav_msgs::Path::ConstPtr &via_points_msg)
Callback for custom via-points.
Definition: teb_local_planner_ros.cpp:1062
teb_local_planner::TebLocalPlannerROS::configureBackupModes
void configureBackupModes(std::vector< geometry_msgs::PoseStamped > &transformed_plan, int &goal_idx)
Definition: teb_local_planner_ros.cpp:982
teb_local_planner::TebLocalPlannerROS::failure_detector_
FailureDetector failure_detector_
Detect if the robot got stucked.
Definition: teb_local_planner_ros.h:446
teb_local_planner::TebLocalPlannerROS::cancel
bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
Definition: teb_local_planner_ros.h:214
teb_local_planner::TebLocalPlannerROS::goal_reached_
bool goal_reached_
store whether the goal is reached or not
Definition: teb_local_planner_ros.h:467
teb_local_planner::TebLocalPlannerROS::tf_
tf2_ros::Buffer * tf_
pointer to tf buffer
Definition: teb_local_planner_ros.h:437
teb_local_planner::TebLocalPlannerROS::updateObstacleContainerWithCustomObstacles
void updateObstacleContainerWithCustomObstacles()
Update internal obstacle vector based on custom messages received via subscriber.
Definition: teb_local_planner_ros.cpp:588
teb_local_planner::TebLocalPlannerROS::saturateVelocity
void saturateVelocity(double &vx, double &vy, double &omega, double max_vel_x, double max_vel_y, double max_vel_trans, double max_vel_theta, double max_vel_x_backwards) const
Saturate the translational and angular velocity to given limits.
Definition: teb_local_planner_ros.cpp:910
ros::Time
teb_local_planner::TebLocalPlannerROS::global_plan_
std::vector< geometry_msgs::PoseStamped > global_plan_
Store the current global plan.
Definition: teb_local_planner_ros.h:448
teb_local_planner::TebLocalPlannerROS::setPlan
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the teb local planner is following.
Definition: teb_local_planner_ros.cpp:239
teb_local_planner::TebLocalPlannerROS::isGoalReached
bool isGoalReached()
Check if the goal pose has been achieved.
Definition: teb_local_planner_ros.cpp:501
teb_local_planner::TebLocalPlannerROS::costmap_converter_
boost::shared_ptr< costmap_converter::BaseCostmapToPolygons > costmap_converter_
Store the current costmap_converter
Definition: teb_local_planner_ros.h:453
teb_local_planner::TebLocalPlannerROS::robot_circumscribed_radius
double robot_circumscribed_radius
The radius of the circumscribed circle of the robot.
Definition: teb_local_planner_ros.h:476
teb_local_planner::TebLocalPlannerROS::costmap_model_
boost::shared_ptr< base_local_planner::CostmapModel > costmap_model_
Definition: teb_local_planner_ros.h:444
teb_local_planner::TebLocalPlannerROS::pruneGlobalPlan
bool pruneGlobalPlan(const tf2_ros::Buffer &tf, const geometry_msgs::PoseStamped &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.
Definition: teb_local_planner_ros.cpp:693
tf
teb_local_planner::PlannerInterfacePtr
boost::shared_ptr< PlannerInterface > PlannerInterfacePtr
Abbrev. for shared instances of PlannerInterface or it's subclasses.
Definition: planner_interface.h:239
costmap_controller.h
optimal_planner.h
teb_local_planner::TebLocalPlannerROS::custom_obst_sub_
ros::Subscriber custom_obst_sub_
Subscriber for custom obstacles received via a ObstacleMsg.
Definition: teb_local_planner_ros.h:456
teb_local_planner::TebLocalPlannerROS::getNumberFromXMLRPC
static double getNumberFromXMLRPC(XmlRpc::XmlRpcValue &value, const std::string &full_param_name)
Get a number from the given XmlRpcValue.
Definition: teb_local_planner_ros.cpp:1241
costmap_converter_interface.h
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::ViaPointContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ViaPointContainer
Typedef for a container storing via-points.
Definition: optimal_planner.h:118
teb_local_planner::TebLocalPlannerROS::last_preferred_rotdir_
RotType last_preferred_rotdir_
Store recent preferred turning direction.
Definition: teb_local_planner_ros.h:471
odometry_helper_ros.h
teb_local_planner::TebLocalPlannerROS::footprint_spec_
std::vector< geometry_msgs::Point > footprint_spec_
Store the footprint of the robot.
Definition: teb_local_planner_ros.h:474
teb_local_planner::TebLocalPlannerROS::initialized_
bool initialized_
Keeps track about the correct initialization of this class.
Definition: teb_local_planner_ros.h:483
visualization.h
costmap_2d::Costmap2DROS
XmlRpc::XmlRpcValue
nav_core::BaseLocalPlanner
teb_local_planner::TebLocalPlannerROS::last_cmd_
geometry_msgs::Twist last_cmd_
Store the last control command generated in computeVelocityCommands()
Definition: teb_local_planner_ros.h:472
ros::NodeHandle
ros::Subscriber
teb_local_planner::TebLocalPlannerROS::reconfigureCB
void reconfigureCB(TebLocalPlannerReconfigureConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
Definition: teb_local_planner_ros.cpp:117
teb_local_planner::TebLocalPlannerROS::obstacles_
ObstContainer obstacles_
Obstacle vector that should be considered during local trajectory optimization.
Definition: teb_local_planner_ros.h:441


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15