teb_config.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_CONFIG_H_
40 #define TEB_CONFIG_H_
41 
42 #include <ros/console.h>
43 #include <ros/ros.h>
44 #include <Eigen/Core>
45 #include <Eigen/StdVector>
46 
47 #include <teb_local_planner/TebLocalPlannerReconfigureConfig.h>
49 
50 
51 // Definitions
52 #define USE_ANALYTIC_JACOBI // if available for a specific edge, use analytic jacobi
53 
54 
55 namespace teb_local_planner
56 {
57 
62 class TebConfig
63 {
64 public:
65 
66  std::string odom_topic;
67  std::string map_frame;
68 
70 
72  struct Trajectory
73  {
74  double teb_autosize;
75  double dt_ref;
76  double dt_hysteresis;
94  } trajectory;
95 
97  struct Robot
98  {
99  double max_vel_x;
101  double max_vel_y;
102  double max_vel_trans;
103  double max_vel_theta;
104  double acc_lim_x;
105  double acc_lim_y;
106  double acc_lim_theta;
108  double wheelbase;
110  bool is_footprint_dynamic; //<! If true, updated the footprint before checking trajectory feasibility
111  bool use_proportional_saturation; //<! If true, reduce all twists components (linear x and y, and angular z) proportionally if any exceed its corresponding bounds, instead of saturating each one individually
112  double transform_tolerance = 0.5; //<! Tolerance when querying the TF Tree for a transformation (seconds)
113  } robot;
114 
117  {
123  bool complete_global_plan; // true prevents the robot from ending the path early when it cross the end goal
124  } goal_tolerance;
125 
127  struct Obstacles
128  {
130  double inflation_dist;
145  } obstacles;
146 
147 
150  {
153 
156 
158 
177 
180  } optim;
181 
182 
184  {
197 
203 
206 
208 
215  } hcp;
216 
218  struct Recovery
219  {
229  } recovery;
230 
231 
246  {
247 
248  odom_topic = "odom";
249  map_frame = "odom";
250  robot_model = boost::make_shared<PointRobotFootprint>();
251 
252  // Trajectory
253 
254  trajectory.teb_autosize = true;
255  trajectory.dt_ref = 0.3;
258  trajectory.max_samples = 500;
274 
275  // Robot
276 
277  robot.max_vel_x = 0.4;
279  robot.max_vel_y = 0.0;
280  robot.max_vel_trans = 0.0;
281  robot.max_vel_theta = 0.3;
282  robot.acc_lim_x = 0.5;
283  robot.acc_lim_y = 0.5;
284  robot.acc_lim_theta = 0.5;
286  robot.wheelbase = 1.0;
288  robot.is_footprint_dynamic = false;
290 
291  // GoalTolerance
292 
299 
300  // Obstacles
301 
318 
319  // Optimization
320 
324  optim.optimization_verbose = false;
325  optim.penalty_epsilon = 0.05;
326  optim.weight_max_vel_x = 2; //1
337  optim.weight_obstacle = 50;
338  optim.weight_inflation = 0.1;
344 
347 
348  // Homotopy Class Planner
349 
351  hcp.enable_multithreading = true;
352  hcp.simple_exploration = false;
360 
364  hcp.roadmap_graph_area_width = 6; // [m]
369 
371 
372  hcp.visualize_hc_graph = false;
375  hcp.detours_orientation_tolerance = M_PI / 2.0;
378 
379  // Recovery
380 
388 
389 
390  }
391 
397 
406  void reconfigure(TebLocalPlannerReconfigureConfig& cfg);
407 
414  void checkParameters() const;
415 
420  void checkDeprecated(const ros::NodeHandle& nh) const;
421 
425  boost::mutex& configMutex() {return config_mutex_;}
426 
427 private:
428  boost::mutex config_mutex_;
429 
430 };
431 
432 
433 } // namespace teb_local_planner
434 
435 #endif
teb_local_planner::TebConfig::Robot::transform_tolerance
double transform_tolerance
Definition: teb_config.h:112
teb_local_planner::TebConfig::HomotopyClasses::switching_blocking_period
double switching_blocking_period
Specify a time duration in seconds that needs to be expired before a switch to new equivalence class ...
Definition: teb_config.h:196
teb_local_planner::TebConfig::Robot::max_vel_y
double max_vel_y
Maximum strafing velocity of the robot (should be zero for non-holonomic robots!)
Definition: teb_config.h:101
teb_local_planner::TebConfig::Trajectory::force_reinit_new_goal_angular
double force_reinit_new_goal_angular
Reinitialize the trajectory if a previous goal is updated with an angular difference of more than the...
Definition: teb_config.h:87
teb_local_planner::TebConfig::Obstacles::obstacle_association_cutoff_factor
double obstacle_association_cutoff_factor
See obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist a...
Definition: teb_config.h:138
teb_local_planner::TebConfig::Trajectory::exact_arc_length
bool exact_arc_length
If true, the planner uses the exact arc length in velocity, acceleration and turning rate computation...
Definition: teb_config.h:85
teb_local_planner::TebConfig::Optimization::weight_viapoint
double weight_viapoint
Optimization weight for minimizing the distance to via-points.
Definition: teb_config.h:175
teb_local_planner::TebConfig::Obstacles::inflation_dist
double inflation_dist
buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in ...
Definition: teb_config.h:130
teb_local_planner::TebConfig::Optimization::weight_dynamic_obstacle
double weight_dynamic_obstacle
Optimization weight for satisfying a minimum separation from dynamic obstacles.
Definition: teb_config.h:172
teb_local_planner::TebConfig::checkParameters
void checkParameters() const
Check parameters and print warnings in case of discrepancies.
Definition: teb_config.cpp:343
teb_local_planner::TebConfig::Obstacles::obstacle_proximity_ratio_max_vel
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...
Definition: teb_config.h:142
teb_local_planner::TebConfig::Robot::max_vel_trans
double max_vel_trans
Maximum translational velocity of the robot for omni robots, which is different from max_vel_x.
Definition: teb_config.h:102
boost::shared_ptr< BaseRobotFootprintModel >
teb_local_planner::TebConfig::HomotopyClasses::roadmap_graph_area_width
double roadmap_graph_area_width
< Specify the number of samples generated for creating the roadmap graph, if simple_exploration is tu...
Definition: teb_config.h:199
teb_local_planner::TebConfig::Optimization::weight_prefer_rotdir
double weight_prefer_rotdir
Optimization weight for preferring a specific turning direction (-> currently only activated if an os...
Definition: teb_config.h:176
teb_local_planner::TebConfig::Optimization::weight_acc_lim_x
double weight_acc_lim_x
Optimization weight for satisfying the maximum allowed translational acceleration.
Definition: teb_config.h:162
teb_local_planner::TebConfig::Trajectory::dt_ref
double dt_ref
Desired temporal resolution of the trajectory (should be in the magniture of the underlying control r...
Definition: teb_config.h:75
teb_local_planner::TebConfig::GoalTolerance::complete_global_plan
bool complete_global_plan
Definition: teb_config.h:123
teb_local_planner::TebConfig::checkDeprecated
void checkDeprecated(const ros::NodeHandle &nh) const
Check if some deprecated parameters are found and print warnings.
Definition: teb_config.cpp:412
teb_local_planner::TebConfig::HomotopyClasses::max_ratio_detours_duration_best_duration
double max_ratio_detours_duration_best_duration
Detours are discarted if their execution time / the execution time of the best teb is > this.
Definition: teb_config.h:214
teb_local_planner::TebConfig::configMutex
boost::mutex & configMutex()
Return the internal config mutex.
Definition: teb_config.h:425
ros.h
teb_local_planner::TebConfig::HomotopyClasses::selection_dropping_probability
double selection_dropping_probability
At each planning cycle, TEBs other than the current 'best' one will be randomly dropped with this pro...
Definition: teb_config.h:195
teb_local_planner::TebConfig::Trajectory::teb_autosize
double teb_autosize
Enable automatic resizing of the trajectory w.r.t to the temporal resolution (recommended)
Definition: teb_config.h:74
teb_local_planner::TebConfig::Trajectory::publish_feedback
bool publish_feedback
Publish planner feedback containing the full trajectory and a list of active obstacles (should be ena...
Definition: teb_config.h:90
teb_local_planner::TebConfig::loadRosParamFromNodeHandle
void loadRosParamFromNodeHandle(const ros::NodeHandle &nh)
Load parmeters from the ros param server.
Definition: teb_config.cpp:80
teb_local_planner::TebConfig::Obstacles::dynamic_obstacle_inflation_dist
double dynamic_obstacle_inflation_dist
Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be la...
Definition: teb_config.h:131
teb_local_planner::TebConfig::Optimization::penalty_epsilon
double penalty_epsilon
Add a small safety margin to penalty functions for hard-constraint approximations.
Definition: teb_config.h:157
teb_local_planner::TebConfig::Trajectory::feasibility_check_lookahead_distance
double feasibility_check_lookahead_distance
Specify up to which distance (and with an index below feasibility_check_no_poses) from the robot the ...
Definition: teb_config.h:89
teb_local_planner::TebConfig::HomotopyClasses::h_signature_threshold
double h_signature_threshold
Two h-signatures are assumed to be equal, if both the difference of real parts and complex parts are ...
Definition: teb_config.h:202
teb_local_planner::TebConfig::GoalTolerance::theta_stopped_vel
double theta_stopped_vel
Below what maximum rotation velocity we consider the robot to be stopped in rotation.
Definition: teb_config.h:122
teb_local_planner::TebConfig::GoalTolerance
Goal tolerance related parameters.
Definition: teb_config.h:116
teb_local_planner::TebConfig::Recovery::oscillation_recovery
bool oscillation_recovery
Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robo...
Definition: teb_config.h:222
teb_local_planner::TebConfig::HomotopyClasses::simple_exploration
bool simple_exploration
If true, distinctive trajectories are explored using a simple left-right approach (pass each obstacle...
Definition: teb_config.h:187
teb_local_planner::TebConfig::hcp
struct teb_local_planner::TebConfig::HomotopyClasses hcp
teb_local_planner::TebConfig::HomotopyClasses::visualize_with_time_as_z_axis_scale
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...
Definition: teb_config.h:210
teb_local_planner::TebConfig::Obstacles::costmap_converter_plugin
std::string costmap_converter_plugin
Define a plugin name of the costmap_converter package (costmap cells are converted to points/lines/po...
Definition: teb_config.h:139
teb_local_planner::TebConfig::HomotopyClasses::delete_detours_backwards
bool delete_detours_backwards
If enabled, the planner will discard the plans detouring backwards with respect to the best plan.
Definition: teb_config.h:211
teb_local_planner::TebConfig::TebConfig
TebConfig()
Construct the TebConfig using default values.
Definition: teb_config.h:245
teb_local_planner::TebConfig::HomotopyClasses::enable_multithreading
bool enable_multithreading
Activate multiple threading for planning multiple trajectories in parallel.
Definition: teb_config.h:186
teb_local_planner::TebConfig::Obstacles::obstacle_association_force_inclusion_factor
double obstacle_association_force_inclusion_factor
The non-legacy obstacle association technique tries to connect only relevant obstacles with the discr...
Definition: teb_config.h:137
teb_local_planner::TebConfig::HomotopyClasses::max_number_plans_in_current_class
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 ...
Definition: teb_config.h:189
teb_local_planner::TebConfig::HomotopyClasses::h_signature_prescaler
double h_signature_prescaler
Scale number of obstacle value in order to allow huge number of obstacles. Do not choose it extremly ...
Definition: teb_config.h:201
teb_local_planner::TebConfig::Obstacles::include_costmap_obstacles
bool include_costmap_obstacles
Specify whether the obstacles in the costmap should be taken into account directly.
Definition: teb_config.h:133
teb_local_planner::TebConfig::Trajectory::global_plan_viapoint_sep
double global_plan_viapoint_sep
Min. separation between each two consecutive via-points extracted from the global plan (if negative: ...
Definition: teb_config.h:81
teb_local_planner::TebConfig::HomotopyClasses::max_number_classes
int max_number_classes
Specify the maximum number of allowed alternative homotopy classes (limits computational effort)
Definition: teb_config.h:188
teb_local_planner::TebConfig::Trajectory::control_look_ahead_poses
int control_look_ahead_poses
Min angular resolution used during the costmap collision check. If not respected, intermediate sample...
Definition: teb_config.h:92
teb_local_planner::TebConfig::GoalTolerance::xy_goal_tolerance
double xy_goal_tolerance
Allowed final euclidean distance to the goal position.
Definition: teb_config.h:119
teb_local_planner::TebConfig::Optimization::no_outer_iterations
int no_outer_iterations
Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with...
Definition: teb_config.h:152
teb_local_planner::TebConfig::Optimization
Optimization related parameters.
Definition: teb_config.h:149
console.h
teb_local_planner::TebConfig::Optimization::no_inner_iterations
int no_inner_iterations
Number of solver iterations called in each outerloop iteration.
Definition: teb_config.h:151
teb_local_planner::TebConfig::Trajectory::dt_hysteresis
double dt_hysteresis
Hysteresis for automatic resizing depending on the current temporal resolution (dt): usually 10% of d...
Definition: teb_config.h:76
teb_local_planner::TebConfig::Recovery::oscillation_filter_duration
double oscillation_filter_duration
Filter length/duration [sec] for the detection of oscillations.
Definition: teb_config.h:226
teb_local_planner::TebConfig::Obstacles::obstacle_proximity_lower_bound
double obstacle_proximity_lower_bound
Distance to a static obstacle for which the velocity should be lower.
Definition: teb_config.h:143
teb_local_planner::TebConfig::Trajectory::min_resolution_collision_check_angular
double min_resolution_collision_check_angular
Definition: teb_config.h:91
teb_local_planner::TebConfig::Optimization::weight_obstacle
double weight_obstacle
Optimization weight for satisfying a minimum separation from obstacles.
Definition: teb_config.h:170
teb_local_planner::TebConfig::recovery
struct teb_local_planner::TebConfig::Recovery recovery
Parameters related to recovery and backup strategies.
teb_local_planner::TebConfig::Optimization::weight_max_vel_x
double weight_max_vel_x
Optimization weight for satisfying the maximum allowed translational velocity.
Definition: teb_config.h:159
teb_local_planner::TebConfig::Optimization::weight_adapt_factor
double weight_adapt_factor
Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer...
Definition: teb_config.h:178
teb_local_planner::TebConfig::Robot::max_vel_x_backwards
double max_vel_x_backwards
Maximum translational velocity of the robot for driving backwards.
Definition: teb_config.h:100
teb_local_planner::TebConfig::Robot::acc_lim_theta
double acc_lim_theta
Maximum angular acceleration of the robot.
Definition: teb_config.h:106
teb_local_planner::TebConfig::Optimization::weight_velocity_obstacle_ratio
double weight_velocity_obstacle_ratio
Optimization weight for satisfying a maximum allowed velocity with respect to the distance to a stati...
Definition: teb_config.h:174
teb_local_planner::TebConfig::Optimization::weight_inflation
double weight_inflation
Optimization weight for the inflation penalty (should be small)
Definition: teb_config.h:171
teb_local_planner::TebConfig::HomotopyClasses::selection_prefer_initial_plan
double selection_prefer_initial_plan
Specify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the ini...
Definition: teb_config.h:191
teb_local_planner::TebConfig::HomotopyClasses::viapoints_all_candidates
bool viapoints_all_candidates
If true, all trajectories of different topologies are attached to the current set of via-points,...
Definition: teb_config.h:207
teb_local_planner::TebConfig::Obstacles::obstacle_proximity_upper_bound
double obstacle_proximity_upper_bound
Distance to a static obstacle for which the velocity should be higher.
Definition: teb_config.h:144
teb_local_planner::TebConfig::HomotopyClasses::length_start_orientation_vector
double length_start_orientation_vector
Length of the vector used to compute the start orientation of a plan.
Definition: teb_config.h:213
teb_local_planner::TebConfig::trajectory
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
teb_local_planner::TebConfig::Obstacles::min_obstacle_dist
double min_obstacle_dist
Minimum desired separation from obstacles.
Definition: teb_config.h:129
teb_local_planner::TebConfig::HomotopyClasses::detours_orientation_tolerance
double detours_orientation_tolerance
A plan is considered a detour if its start orientation differs more than this from the best plan.
Definition: teb_config.h:212
teb_local_planner::TebConfig::Obstacles
Obstacle related parameters.
Definition: teb_config.h:127
teb_local_planner::TebConfig::Trajectory::global_plan_overwrite_orientation
bool global_plan_overwrite_orientation
Overwrite orientation of local subgoals provided by the global planner.
Definition: teb_config.h:79
robot_footprint_model.h
teb_local_planner::TebConfig::Optimization::obstacle_cost_exponent
double obstacle_cost_exponent
Exponent for nonlinear obstacle cost (cost = linear_cost * obstacle_cost_exponent)....
Definition: teb_config.h:179
teb_local_planner::TebConfig::Trajectory::max_samples
int max_samples
Maximum number of samples; Warning: if too small the discretization/resolution might not be sufficien...
Definition: teb_config.h:78
teb_local_planner::TebConfig::robot
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
teb_local_planner::TebConfig::HomotopyClasses
Definition: teb_config.h:183
teb_local_planner::TebConfig::HomotopyClasses::selection_obst_cost_scale
double selection_obst_cost_scale
Extra scaling of obstacle cost terms just for selecting the 'best' candidate.
Definition: teb_config.h:192
teb_local_planner::TebConfig::Trajectory::max_global_plan_lookahead_dist
double max_global_plan_lookahead_dist
Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into a...
Definition: teb_config.h:83
teb_local_planner::TebConfig::GoalTolerance::trans_stopped_vel
double trans_stopped_vel
Below what maximum velocity we consider the robot to be stopped in translation.
Definition: teb_config.h:121
teb_local_planner::TebConfig::Recovery::oscillation_recovery_min_duration
double oscillation_recovery_min_duration
Minumum duration [sec] for which the recovery mode is activated after an oscillation is detected.
Definition: teb_config.h:225
teb_local_planner::TebConfig::Obstacles::costmap_obstacles_behind_robot_dist
double costmap_obstacles_behind_robot_dist
Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify ...
Definition: teb_config.h:134
teb_local_planner::TebConfig::Trajectory::global_plan_prune_distance
double global_plan_prune_distance
Distance between robot and via_points of global plan which is used for pruning.
Definition: teb_config.h:84
teb_local_planner::TebConfig::config_mutex_
boost::mutex config_mutex_
Mutex for config accesses and changes.
Definition: teb_config.h:428
teb_local_planner::TebConfig::HomotopyClasses::selection_cost_hysteresis
double selection_cost_hysteresis
Specify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in...
Definition: teb_config.h:190
teb_local_planner::TebConfig::Trajectory::force_reinit_new_goal_dist
double force_reinit_new_goal_dist
Reinitialize the trajectory if a previous goal is updated with a seperation of more than the specifie...
Definition: teb_config.h:86
teb_local_planner::TebConfig::reconfigure
void reconfigure(TebLocalPlannerReconfigureConfig &cfg)
Reconfigure parameters from the dynamic_reconfigure config. Change parameters dynamically (e....
Definition: teb_config.cpp:221
teb_local_planner::TebConfig::GoalTolerance::yaw_goal_tolerance
double yaw_goal_tolerance
Allowed final orientation error.
Definition: teb_config.h:118
teb_local_planner::TebConfig::Obstacles::costmap_converter_spin_thread
bool costmap_converter_spin_thread
If true, the costmap converter invokes its callback queue in a different thread.
Definition: teb_config.h:140
teb_local_planner::TebConfig::goal_tolerance
struct teb_local_planner::TebConfig::GoalTolerance goal_tolerance
Goal tolerance related parameters.
teb_local_planner::TebConfig::Trajectory::via_points_ordered
bool via_points_ordered
If true, the planner adheres to the order of via-points in the storage container.
Definition: teb_config.h:82
teb_local_planner::TebConfig::Trajectory::allow_init_with_backwards_motion
bool allow_init_with_backwards_motion
If true, the underlying trajectories might be initialized with backwards motions in case the goal is ...
Definition: teb_config.h:80
teb_local_planner::TebConfig::HomotopyClasses::selection_viapoint_cost_scale
double selection_viapoint_cost_scale
Extra scaling of via-point cost terms just for selecting the 'best' candidate.
Definition: teb_config.h:193
teb_local_planner::TebConfig::Robot::use_proportional_saturation
bool use_proportional_saturation
Definition: teb_config.h:111
teb_local_planner::TebConfig::Optimization::weight_optimaltime
double weight_optimaltime
Optimization weight for contracting the trajectory w.r.t. transition time.
Definition: teb_config.h:168
teb_local_planner::TebConfig
Config class for the teb_local_planner and its components.
Definition: teb_config.h:62
teb_local_planner::TebConfig::HomotopyClasses::obstacle_heading_threshold
double obstacle_heading_threshold
Specify the value of the normalized scalar product between obstacle heading and goal heading in order...
Definition: teb_config.h:205
teb_local_planner::TebConfig::Robot::max_vel_x
double max_vel_x
Maximum translational velocity of the robot.
Definition: teb_config.h:99
teb_local_planner::TebConfig::obstacles
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
teb_local_planner::TebConfig::map_frame
std::string map_frame
Global planning frame.
Definition: teb_config.h:67
teb_local_planner::TebConfig::GoalTolerance::free_goal_vel
bool free_goal_vel
Allow the robot's velocity to be nonzero (usally max_vel) for planning purposes.
Definition: teb_config.h:120
teb_local_planner::TebConfig::Trajectory::min_samples
int min_samples
Minimum number of samples (should be always greater than 2)
Definition: teb_config.h:77
teb_local_planner::TebConfig::Optimization::weight_acc_lim_y
double weight_acc_lim_y
Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonom...
Definition: teb_config.h:163
teb_local_planner::TebConfig::Optimization::weight_max_vel_y
double weight_max_vel_y
Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic r...
Definition: teb_config.h:160
teb_local_planner::TebConfig::HomotopyClasses::enable_homotopy_class_planning
bool enable_homotopy_class_planning
Activate homotopy class planning (Requires much more resources that simple planning,...
Definition: teb_config.h:185
teb_local_planner::TebConfig::Recovery::oscillation_v_eps
double oscillation_v_eps
Threshold for the average normalized linear velocity: if oscillation_v_eps and oscillation_omega_eps ...
Definition: teb_config.h:223
teb_local_planner::TebConfig::Robot::acc_lim_x
double acc_lim_x
Maximum translational acceleration of the robot.
Definition: teb_config.h:104
teb_local_planner::TebConfig::Optimization::weight_shortest_path
double weight_shortest_path
Optimization weight for contracting the trajectory w.r.t. path length.
Definition: teb_config.h:169
teb_local_planner::TebConfig::Obstacles::costmap_converter_rate
int costmap_converter_rate
The rate that defines how often the costmap_converter plugin processes the current costmap (the value...
Definition: teb_config.h:141
teb_local_planner::TebConfig::Recovery::divergence_detection_enable
bool divergence_detection_enable
True to enable divergence detection.
Definition: teb_config.h:227
teb_local_planner::TebConfig::Optimization::weight_dynamic_obstacle_inflation
double weight_dynamic_obstacle_inflation
Optimization weight for the inflation penalty of dynamic obstacles (should be small)
Definition: teb_config.h:173
teb_local_planner::TebConfig::HomotopyClasses::visualize_hc_graph
bool visualize_hc_graph
Visualize the graph that is created for exploring new homotopy classes.
Definition: teb_config.h:209
teb_local_planner::TebConfig::Recovery::divergence_detection_max_chi_squared
int divergence_detection_max_chi_squared
Maximum acceptable Mahalanobis distance above which it is assumed that the optimization diverged.
Definition: teb_config.h:228
teb_local_planner::TebConfig::Optimization::weight_max_vel_theta
double weight_max_vel_theta
Optimization weight for satisfying the maximum allowed angular velocity.
Definition: teb_config.h:161
teb_local_planner::TebConfig::robot_model
RobotFootprintModelPtr robot_model
model of the robot's footprint
Definition: teb_config.h:69
teb_local_planner::TebConfig::HomotopyClasses::roadmap_graph_area_length_scale
double roadmap_graph_area_length_scale
The length of the rectangular region is determined by the distance between start and goal....
Definition: teb_config.h:200
teb_local_planner::TebConfig::Obstacles::include_dynamic_obstacles
bool include_dynamic_obstacles
Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (t...
Definition: teb_config.h:132
teb_local_planner::TebConfig::Recovery::shrink_horizon_backup
bool shrink_horizon_backup
Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues.
Definition: teb_config.h:220
teb_local_planner::TebConfig::Recovery::shrink_horizon_min_duration
double shrink_horizon_min_duration
Specify minimum duration for the reduced horizon in case an infeasible trajectory is detected.
Definition: teb_config.h:221
teb_local_planner::TebConfig::Trajectory::feasibility_check_no_poses
int feasibility_check_no_poses
Specify up to which pose (under the feasibility_check_lookahead_distance) on the predicted plan the f...
Definition: teb_config.h:88
teb_local_planner::TebConfig::odom_topic
std::string odom_topic
Topic name of the odometry message, provided by the robot driver or simulator.
Definition: teb_config.h:66
teb_local_planner::TebConfig::Optimization::weight_kinematics_forward_drive
double weight_kinematics_forward_drive
Optimization weight for forcing the robot to choose only forward directions (positive transl....
Definition: teb_config.h:166
teb_local_planner::TebConfig::Robot::acc_lim_y
double acc_lim_y
Maximum strafing acceleration of the robot.
Definition: teb_config.h:105
teb_local_planner::TebConfig::HomotopyClasses::obstacle_keypoint_offset
double obstacle_keypoint_offset
If simple_exploration is turned on, this parameter determines the distance on the left and right side...
Definition: teb_config.h:204
teb_local_planner::TebConfig::HomotopyClasses::selection_alternative_time_cost
bool selection_alternative_time_cost
If true, time cost is replaced by the total transition time.
Definition: teb_config.h:194
teb_local_planner::TebConfig::Optimization::weight_kinematics_turning_radius
double weight_kinematics_turning_radius
Optimization weight for enforcing a minimum turning radius (carlike robots)
Definition: teb_config.h:167
teb_local_planner::TebConfig::Recovery
Recovery/backup related parameters.
Definition: teb_config.h:218
teb_local_planner::TebConfig::Trajectory
Trajectory related parameters.
Definition: teb_config.h:72
teb_local_planner::TebConfig::Optimization::weight_acc_lim_theta
double weight_acc_lim_theta
Optimization weight for satisfying the maximum allowed angular acceleration.
Definition: teb_config.h:164
teb_local_planner::TebConfig::Robot::min_turning_radius
double min_turning_radius
Minimum turning radius of a carlike robot (diff-drive robot: zero);.
Definition: teb_config.h:107
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::TebConfig::Obstacles::legacy_obstacle_association
bool legacy_obstacle_association
If true, the old association strategy is used (for each obstacle, find the nearest TEB pose),...
Definition: teb_config.h:136
teb_local_planner::TebConfig::Robot::wheelbase
double wheelbase
The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_a...
Definition: teb_config.h:108
teb_local_planner::TebConfig::Robot::cmd_angle_instead_rotvel
bool cmd_angle_instead_rotvel
Substitute the rotational velocity in the commanded velocity message by the corresponding steering an...
Definition: teb_config.h:109
teb_local_planner::TebConfig::Optimization::optimization_activate
bool optimization_activate
Activate the optimization.
Definition: teb_config.h:154
teb_local_planner::TebConfig::Robot
Robot related parameters.
Definition: teb_config.h:97
teb_local_planner::TebConfig::Optimization::optimization_verbose
bool optimization_verbose
Print verbose information.
Definition: teb_config.h:155
teb_local_planner::TebConfig::Optimization::weight_kinematics_nh
double weight_kinematics_nh
Optimization weight for satisfying the non-holonomic kinematics.
Definition: teb_config.h:165
teb_local_planner::TebConfig::Robot::is_footprint_dynamic
bool is_footprint_dynamic
Definition: teb_config.h:110
teb_local_planner::TebConfig::optim
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
teb_local_planner::TebConfig::Robot::max_vel_theta
double max_vel_theta
Maximum angular velocity of the robot.
Definition: teb_config.h:103
teb_local_planner::TebConfig::Obstacles::obstacle_poses_affected
int obstacle_poses_affected
The obstacle position is attached to the closest pose on the trajectory to reduce computational effor...
Definition: teb_config.h:135
teb_local_planner::TebConfig::HomotopyClasses::roadmap_graph_no_samples
int roadmap_graph_no_samples
Definition: teb_config.h:198
ros::NodeHandle
teb_local_planner::TebConfig::Recovery::oscillation_omega_eps
double oscillation_omega_eps
Threshold for the average normalized angular velocity: if oscillation_v_eps and oscillation_omega_eps...
Definition: teb_config.h:224
teb_local_planner::TebConfig::Trajectory::prevent_look_ahead_poses_near_goal
int prevent_look_ahead_poses_near_goal
Index of the pose used to extract the velocity command.
Definition: teb_config.h:93


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