Go to the documentation of this file.
219 if (cfg.max_vel_trans == 0.0)
311 ROS_WARN(
"TebLocalPlannerROS() Param Warning: Do not choose max_vel_x_backwards to be <=0. Disable backwards driving by increasing the optimization weight for penalyzing backwards driving.");
315 ROS_WARN(
"TebLocalPlannerROS() Param Warning: max_vel_x <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!");
318 ROS_WARN(
"TebLocalPlannerROS() Param Warning: max_vel_x_backwards <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!");
321 ROS_WARN(
"TebLocalPlannerROS() Param Warning: max_vel_theta <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!");
324 ROS_WARN(
"TebLocalPlannerROS() Param Warning: acc_lim_x <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!");
327 ROS_WARN(
"TebLocalPlannerROS() Param Warning: acc_lim_theta <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!");
331 ROS_WARN(
"TebLocalPlannerROS() Param Warning: dt_ref <= dt_hysteresis. The hysteresis is not allowed to be greater or equal!. Undefined behavior... Change at least one of them!");
335 ROS_WARN(
"TebLocalPlannerROS() Param Warning: parameter min_samples is smaller than 3! Sorry, I haven't enough degrees of freedom to plan a trajectory for you. Please increase ...");
339 ROS_WARN(
"TebLocalPlannerROS() Param Warning: parameter 'costmap_obstacles_behind_robot_dist' should be positive or zero.");
343 ROS_WARN(
"TebLocalPlannerROS() Param Warning: parameter obstacle_heading_threshold must be in the interval ]0,1[. 0=0deg opening angle, 1=90deg opening angle.");
347 ROS_WARN(
"TebLocalPlannerROS() Param Warning: parameter cmd_angle_instead_rotvel is non-zero but wheelbase is set to zero: undesired behavior.");
350 ROS_WARN(
"TebLocalPlannerROS() Param Warning: parameter cmd_angle_instead_rotvel is non-zero but min_turning_radius is set to zero: undesired behavior. You are mixing a carlike and a diffdrive robot");
354 ROS_WARN(
"TebLocalPlannerROS() Param Warning: parameter weight_adapt_factor shoud be >= 1.0");
357 ROS_WARN(
"TebLocalPlannerROS() Param Warning: parameter oscillation_filter_duration must be >= 0");
361 ROS_WARN(
"TebLocalPlannerROS() Param Warning: parameter weight_optimaltime shoud be > 0 (even if weight_shortest_path is in use)");
366 ROS_WARN(
"TebLocalPlannerROS() Param Warning: max_vel_trans < min(max_vel_x, max_vel_y). Note that vel_trans = sqrt(Vx^2 + Vy^2), thus max_vel_trans will limit Vx and Vy in the optimization step.");
370 ROS_WARN(
"TebLocalPlannerROS() Param Warning: max_vel_trans > max(max_vel_x, max_vel_y). Robot will rotate and move diagonally to achieve max resultant vel (possibly max vel on both axis), limited by the max_vel_trans.");
378 if (nh.
hasParam(
"line_obstacle_poses_affected") || nh.
hasParam(
"polygon_obstacle_poses_affected"))
379 ROS_WARN(
"TebLocalPlannerROS() Param Warning: 'line_obstacle_poses_affected' and 'polygon_obstacle_poses_affected' are deprecated. They share now the common parameter 'obstacle_poses_affected'.");
381 if (nh.
hasParam(
"weight_point_obstacle") || nh.
hasParam(
"weight_line_obstacle") || nh.
hasParam(
"weight_poly_obstacle"))
382 ROS_WARN(
"TebLocalPlannerROS() Param Warning: 'weight_point_obstacle', 'weight_line_obstacle' and 'weight_poly_obstacle' are deprecated. They are replaced by the single param 'weight_obstacle'.");
384 if (nh.
hasParam(
"costmap_obstacles_front_only"))
385 ROS_WARN(
"TebLocalPlannerROS() Param Warning: 'costmap_obstacles_front_only' is deprecated. It is replaced by 'costmap_obstacles_behind_robot_dist' to define the actual area taken into account.");
387 if (nh.
hasParam(
"costmap_emergency_stop_dist"))
388 ROS_WARN(
"TebLocalPlannerROS() Param Warning: 'costmap_emergency_stop_dist' is deprecated. You can safely remove it from your parameter config.");
390 if (nh.
hasParam(
"alternative_time_cost"))
391 ROS_WARN(
"TebLocalPlannerROS() Param Warning: 'alternative_time_cost' is deprecated. It has been replaced by 'selection_alternative_time_cost'.");
393 if (nh.
hasParam(
"global_plan_via_point_sep"))
394 ROS_WARN(
"TebLocalPlannerROS() Param Warning: 'global_plan_via_point_sep' is deprecated. It has been replaced by 'global_plan_viapoint_sep' due to consistency reasons.");
double transform_tolerance
void setParam(const std::string &key, bool b) const
double switching_blocking_period
Specify a time duration in seconds that needs to be expired before a switch to new equivalence class ...
double max_vel_y
Maximum strafing velocity of the robot (should be zero for non-holonomic robots!)
double force_reinit_new_goal_angular
Reinitialize the trajectory if a previous goal is updated with an angular difference of more than the...
double obstacle_association_cutoff_factor
See obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist a...
bool exact_arc_length
If true, the planner uses the exact arc length in velocity, acceleration and turning rate computation...
double weight_viapoint
Optimization weight for minimizing the distance to via-points.
double inflation_dist
buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in ...
double weight_dynamic_obstacle
Optimization weight for satisfying a minimum separation from dynamic obstacles.
void checkParameters() const
Check parameters and print warnings in case of discrepancies.
double obstacle_proximity_ratio_max_vel
Ratio of the maximum velocities used as an upper bound when reducing the speed due to the proximity t...
double max_vel_trans
Maximum translational velocity of the robot for omni robots, which is different from max_vel_x.
double roadmap_graph_area_width
< Specify the number of samples generated for creating the roadmap graph, if simple_exploration is tu...
double weight_prefer_rotdir
Optimization weight for preferring a specific turning direction (-> currently only activated if an os...
double weight_acc_lim_x
Optimization weight for satisfying the maximum allowed translational acceleration.
double dt_ref
Desired temporal resolution of the trajectory (should be in the magniture of the underlying control r...
bool complete_global_plan
void checkDeprecated(const ros::NodeHandle &nh) const
Check if some deprecated parameters are found and print warnings.
double max_ratio_detours_duration_best_duration
Detours are discarted if their execution time / the execution time of the best teb is > this.
bool getParam(const std::string &key, bool &b) const
double selection_dropping_probability
At each planning cycle, TEBs other than the current 'best' one will be randomly dropped with this pro...
double teb_autosize
Enable automatic resizing of the trajectory w.r.t to the temporal resolution (recommended)
bool publish_feedback
Publish planner feedback containing the full trajectory and a list of active obstacles (should be ena...
void loadRosParamFromNodeHandle(const ros::NodeHandle &nh)
Load parmeters from the ros param server.
double dynamic_obstacle_inflation_dist
Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be la...
double penalty_epsilon
Add a small safety margin to penalty functions for hard-constraint approximations.
double feasibility_check_lookahead_distance
Specify up to which distance (and with an index below feasibility_check_no_poses) from the robot the ...
double h_signature_threshold
Two h-signatures are assumed to be equal, if both the difference of real parts and complex parts are ...
double theta_stopped_vel
Below what maximum rotation velocity we consider the robot to be stopped in rotation.
bool oscillation_recovery
Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robo...
bool simple_exploration
If true, distinctive trajectories are explored using a simple left-right approach (pass each obstacle...
struct teb_local_planner::TebConfig::HomotopyClasses hcp
double visualize_with_time_as_z_axis_scale
If this value is bigger than 0, the trajectory and obstacles are visualized in 3d using the time as t...
std::string costmap_converter_plugin
Define a plugin name of the costmap_converter package (costmap cells are converted to points/lines/po...
bool delete_detours_backwards
If enabled, the planner will discard the plans detouring backwards with respect to the best plan.
bool enable_multithreading
Activate multiple threading for planning multiple trajectories in parallel.
double obstacle_association_force_inclusion_factor
The non-legacy obstacle association technique tries to connect only relevant obstacles with the discr...
int max_number_plans_in_current_class
Specify the maximum number of trajectories to try that are in the same homotopy class as the current ...
double h_signature_prescaler
Scale number of obstacle value in order to allow huge number of obstacles. Do not choose it extremly ...
bool include_costmap_obstacles
Specify whether the obstacles in the costmap should be taken into account directly.
double global_plan_viapoint_sep
Min. separation between each two consecutive via-points extracted from the global plan (if negative: ...
int max_number_classes
Specify the maximum number of allowed alternative homotopy classes (limits computational effort)
int control_look_ahead_poses
Min angular resolution used during the costmap collision check. If not respected, intermediate sample...
double xy_goal_tolerance
Allowed final euclidean distance to the goal position.
int no_outer_iterations
Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with...
int no_inner_iterations
Number of solver iterations called in each outerloop iteration.
double dt_hysteresis
Hysteresis for automatic resizing depending on the current temporal resolution (dt): usually 10% of d...
double oscillation_filter_duration
Filter length/duration [sec] for the detection of oscillations.
double obstacle_proximity_lower_bound
Distance to a static obstacle for which the velocity should be lower.
double min_resolution_collision_check_angular
double weight_obstacle
Optimization weight for satisfying a minimum separation from obstacles.
struct teb_local_planner::TebConfig::Recovery recovery
Parameters related to recovery and backup strategies.
double weight_max_vel_x
Optimization weight for satisfying the maximum allowed translational velocity.
double weight_adapt_factor
Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer...
double max_vel_x_backwards
Maximum translational velocity of the robot for driving backwards.
double acc_lim_theta
Maximum angular acceleration of the robot.
double weight_velocity_obstacle_ratio
Optimization weight for satisfying a maximum allowed velocity with respect to the distance to a stati...
double weight_inflation
Optimization weight for the inflation penalty (should be small)
double selection_prefer_initial_plan
Specify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the ini...
bool viapoints_all_candidates
If true, all trajectories of different topologies are attached to the current set of via-points,...
double obstacle_proximity_upper_bound
Distance to a static obstacle for which the velocity should be higher.
double length_start_orientation_vector
Length of the vector used to compute the start orientation of a plan.
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
double min_obstacle_dist
Minimum desired separation from obstacles.
double detours_orientation_tolerance
A plan is considered a detour if its start orientation differs more than this from the best plan.
bool global_plan_overwrite_orientation
Overwrite orientation of local subgoals provided by the global planner.
double obstacle_cost_exponent
Exponent for nonlinear obstacle cost (cost = linear_cost * obstacle_cost_exponent)....
int max_samples
Maximum number of samples; Warning: if too small the discretization/resolution might not be sufficien...
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
double selection_obst_cost_scale
Extra scaling of obstacle cost terms just for selecting the 'best' candidate.
double max_global_plan_lookahead_dist
Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into a...
bool hasParam(const std::string &key) const
double trans_stopped_vel
Below what maximum velocity we consider the robot to be stopped in translation.
double oscillation_recovery_min_duration
Minumum duration [sec] for which the recovery mode is activated after an oscillation is detected.
double costmap_obstacles_behind_robot_dist
Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify ...
double global_plan_prune_distance
Distance between robot and via_points of global plan which is used for pruning.
#define ROS_INFO_STREAM(args)
boost::mutex config_mutex_
Mutex for config accesses and changes.
double selection_cost_hysteresis
Specify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in...
double force_reinit_new_goal_dist
Reinitialize the trajectory if a previous goal is updated with a seperation of more than the specifie...
void reconfigure(TebLocalPlannerReconfigureConfig &cfg)
Reconfigure parameters from the dynamic_reconfigure config. Change parameters dynamically (e....
double yaw_goal_tolerance
Allowed final orientation error.
bool costmap_converter_spin_thread
If true, the costmap converter invokes its callback queue in a different thread.
struct teb_local_planner::TebConfig::GoalTolerance goal_tolerance
Goal tolerance related parameters.
bool via_points_ordered
If true, the planner adheres to the order of via-points in the storage container.
bool allow_init_with_backwards_motion
If true, the underlying trajectories might be initialized with backwards motions in case the goal is ...
double selection_viapoint_cost_scale
Extra scaling of via-point cost terms just for selecting the 'best' candidate.
bool use_proportional_saturation
double weight_optimaltime
Optimization weight for contracting the trajectory w.r.t. transition time.
double obstacle_heading_threshold
Specify the value of the normalized scalar product between obstacle heading and goal heading in order...
double max_vel_x
Maximum translational velocity of the robot.
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
std::string map_frame
Global planning frame.
bool free_goal_vel
Allow the robot's velocity to be nonzero (usally max_vel) for planning purposes.
int min_samples
Minimum number of samples (should be always greater than 2)
double weight_acc_lim_y
Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonom...
double weight_max_vel_y
Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic r...
bool enable_homotopy_class_planning
Activate homotopy class planning (Requires much more resources that simple planning,...
double oscillation_v_eps
Threshold for the average normalized linear velocity: if oscillation_v_eps and oscillation_omega_eps ...
double acc_lim_x
Maximum translational acceleration of the robot.
double weight_shortest_path
Optimization weight for contracting the trajectory w.r.t. path length.
bool divergence_detection_enable
True to enable divergence detection.
double weight_dynamic_obstacle_inflation
Optimization weight for the inflation penalty of dynamic obstacles (should be small)
bool visualize_hc_graph
Visualize the graph that is created for exploring new homotopy classes.
int divergence_detection_max_chi_squared
Maximum acceptable Mahalanobis distance above which it is assumed that the optimization diverged.
double weight_max_vel_theta
Optimization weight for satisfying the maximum allowed angular velocity.
T param(const std::string ¶m_name, const T &default_val) const
double roadmap_graph_area_length_scale
The length of the rectangular region is determined by the distance between start and goal....
bool include_dynamic_obstacles
Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (t...
bool shrink_horizon_backup
Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues.
double shrink_horizon_min_duration
Specify minimum duration for the reduced horizon in case an infeasible trajectory is detected.
int feasibility_check_no_poses
Specify up to which pose (under the feasibility_check_lookahead_distance) on the predicted plan the f...
std::string odom_topic
Topic name of the odometry message, provided by the robot driver or simulator.
double weight_kinematics_forward_drive
Optimization weight for forcing the robot to choose only forward directions (positive transl....
double acc_lim_y
Maximum strafing acceleration of the robot.
double obstacle_keypoint_offset
If simple_exploration is turned on, this parameter determines the distance on the left and right side...
bool selection_alternative_time_cost
If true, time cost is replaced by the total transition time.
double weight_kinematics_turning_radius
Optimization weight for enforcing a minimum turning radius (carlike robots)
double weight_acc_lim_theta
Optimization weight for satisfying the maximum allowed angular acceleration.
double min_turning_radius
Minimum turning radius of a carlike robot (diff-drive robot: zero);.
bool legacy_obstacle_association
If true, the old association strategy is used (for each obstacle, find the nearest TEB pose),...
double wheelbase
The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_a...
bool cmd_angle_instead_rotvel
Substitute the rotational velocity in the commanded velocity message by the corresponding steering an...
bool optimization_activate
Activate the optimization.
bool optimization_verbose
Print verbose information.
double weight_kinematics_nh
Optimization weight for satisfying the non-holonomic kinematics.
bool is_footprint_dynamic
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
double max_vel_theta
Maximum angular velocity of the robot.
int obstacle_poses_affected
The obstacle position is attached to the closest pose on the trajectory to reduce computational effor...
int roadmap_graph_no_samples
double oscillation_omega_eps
Threshold for the average normalized angular velocity: if oscillation_v_eps and oscillation_omega_eps...
int prevent_look_ahead_poses_near_goal
Index of the pose used to extract the velocity command.
teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15