teb_config.cpp
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 
40 
41 namespace teb_local_planner
42 {
43 
45 {
46 
47  nh.param("odom_topic", odom_topic, odom_topic);
48  nh.param("map_frame", map_frame, map_frame);
49 
50  // Trajectory
52  nh.param("dt_ref", trajectory.dt_ref, trajectory.dt_ref);
58  nh.getParam("global_plan_via_point_sep", trajectory.global_plan_viapoint_sep); // deprecated, see checkDeprecated()
59  if (!nh.param("global_plan_viapoint_sep", trajectory.global_plan_viapoint_sep, trajectory.global_plan_viapoint_sep))
60  nh.setParam("global_plan_viapoint_sep", trajectory.global_plan_viapoint_sep); // write deprecated value to param server
73 
74  // Robot
75  nh.param("max_vel_x", robot.max_vel_x, robot.max_vel_x);
76  nh.param("max_vel_x_backwards", robot.max_vel_x_backwards, robot.max_vel_x_backwards);
77  nh.param("max_vel_y", robot.max_vel_y, robot.max_vel_y);
78  nh.param("max_vel_trans", robot.max_vel_trans, robot.max_vel_trans);
79  nh.param("max_vel_theta", robot.max_vel_theta, robot.max_vel_theta);
80  nh.param("acc_lim_x", robot.acc_lim_x, robot.acc_lim_x);
81  nh.param("acc_lim_y", robot.acc_lim_y, robot.acc_lim_y);
82  nh.param("acc_lim_theta", robot.acc_lim_theta, robot.acc_lim_theta);
83  nh.param("min_turning_radius", robot.min_turning_radius, robot.min_turning_radius);
84  nh.param("wheelbase", robot.wheelbase, robot.wheelbase);
85  nh.param("cmd_angle_instead_rotvel", robot.cmd_angle_instead_rotvel, robot.cmd_angle_instead_rotvel);
86  nh.param("is_footprint_dynamic", robot.is_footprint_dynamic, robot.is_footprint_dynamic);
87  nh.param("use_proportional_saturation", robot.use_proportional_saturation, robot.use_proportional_saturation);
88  nh.param("transform_tolerance", robot.transform_tolerance, robot.transform_tolerance);
89 
90  // GoalTolerance
97 
98  // Obstacles
100  nh.param("inflation_dist", obstacles.inflation_dist, obstacles.inflation_dist);
114 
115  // Optimization
116  nh.param("no_inner_iterations", optim.no_inner_iterations, optim.no_inner_iterations);
117  nh.param("no_outer_iterations", optim.no_outer_iterations, optim.no_outer_iterations);
118  nh.param("optimization_activate", optim.optimization_activate, optim.optimization_activate);
119  nh.param("optimization_verbose", optim.optimization_verbose, optim.optimization_verbose);
120  nh.param("penalty_epsilon", optim.penalty_epsilon, optim.penalty_epsilon);
121  nh.param("weight_max_vel_x", optim.weight_max_vel_x, optim.weight_max_vel_x);
122  nh.param("weight_max_vel_y", optim.weight_max_vel_y, optim.weight_max_vel_y);
123  nh.param("weight_max_vel_theta", optim.weight_max_vel_theta, optim.weight_max_vel_theta);
124  nh.param("weight_acc_lim_x", optim.weight_acc_lim_x, optim.weight_acc_lim_x);
125  nh.param("weight_acc_lim_y", optim.weight_acc_lim_y, optim.weight_acc_lim_y);
126  nh.param("weight_acc_lim_theta", optim.weight_acc_lim_theta, optim.weight_acc_lim_theta);
127  nh.param("weight_kinematics_nh", optim.weight_kinematics_nh, optim.weight_kinematics_nh);
128  nh.param("weight_kinematics_forward_drive", optim.weight_kinematics_forward_drive, optim.weight_kinematics_forward_drive);
129  nh.param("weight_kinematics_turning_radius", optim.weight_kinematics_turning_radius, optim.weight_kinematics_turning_radius);
130  nh.param("weight_optimaltime", optim.weight_optimaltime, optim.weight_optimaltime);
131  nh.param("weight_shortest_path", optim.weight_shortest_path, optim.weight_shortest_path);
132  nh.param("weight_obstacle", optim.weight_obstacle, optim.weight_obstacle);
133  nh.param("weight_inflation", optim.weight_inflation, optim.weight_inflation);
134  nh.param("weight_dynamic_obstacle", optim.weight_dynamic_obstacle, optim.weight_dynamic_obstacle);
135  nh.param("weight_dynamic_obstacle_inflation", optim.weight_dynamic_obstacle_inflation, optim.weight_dynamic_obstacle_inflation);
136  nh.param("weight_velocity_obstacle_ratio", optim.weight_velocity_obstacle_ratio, optim.weight_velocity_obstacle_ratio);
137  nh.param("weight_viapoint", optim.weight_viapoint, optim.weight_viapoint);
138  nh.param("weight_prefer_rotdir", optim.weight_prefer_rotdir, optim.weight_prefer_rotdir);
139  nh.param("weight_adapt_factor", optim.weight_adapt_factor, optim.weight_adapt_factor);
140  nh.param("obstacle_cost_exponent", optim.obstacle_cost_exponent, optim.obstacle_cost_exponent);
141 
142  // Homotopy Class Planner
143  nh.param("enable_homotopy_class_planning", hcp.enable_homotopy_class_planning, hcp.enable_homotopy_class_planning);
144  nh.param("enable_multithreading", hcp.enable_multithreading, hcp.enable_multithreading);
145  nh.param("simple_exploration", hcp.simple_exploration, hcp.simple_exploration);
146  nh.param("max_number_classes", hcp.max_number_classes, hcp.max_number_classes);
147  nh.param("max_number_plans_in_current_class", hcp.max_number_plans_in_current_class, hcp.max_number_plans_in_current_class);
148  nh.param("selection_obst_cost_scale", hcp.selection_obst_cost_scale, hcp.selection_obst_cost_scale);
149  nh.param("selection_prefer_initial_plan", hcp.selection_prefer_initial_plan, hcp.selection_prefer_initial_plan);
150  nh.param("selection_viapoint_cost_scale", hcp.selection_viapoint_cost_scale, hcp.selection_viapoint_cost_scale);
151  nh.param("selection_cost_hysteresis", hcp.selection_cost_hysteresis, hcp.selection_cost_hysteresis);
152  nh.param("selection_alternative_time_cost", hcp.selection_alternative_time_cost, hcp.selection_alternative_time_cost);
153  nh.param("selection_dropping_probability", hcp.selection_dropping_probability, hcp.selection_dropping_probability);
154  nh.param("switching_blocking_period", hcp.switching_blocking_period, hcp.switching_blocking_period);
155  nh.param("roadmap_graph_samples", hcp.roadmap_graph_no_samples, hcp.roadmap_graph_no_samples);
156  nh.param("roadmap_graph_area_width", hcp.roadmap_graph_area_width, hcp.roadmap_graph_area_width);
157  nh.param("roadmap_graph_area_length_scale", hcp.roadmap_graph_area_length_scale, hcp.roadmap_graph_area_length_scale);
158  nh.param("h_signature_prescaler", hcp.h_signature_prescaler, hcp.h_signature_prescaler);
159  nh.param("h_signature_threshold", hcp.h_signature_threshold, hcp.h_signature_threshold);
160  nh.param("obstacle_keypoint_offset", hcp.obstacle_keypoint_offset, hcp.obstacle_keypoint_offset);
161  nh.param("obstacle_heading_threshold", hcp.obstacle_heading_threshold, hcp.obstacle_heading_threshold);
162  nh.param("viapoints_all_candidates", hcp.viapoints_all_candidates, hcp.viapoints_all_candidates);
163  nh.param("visualize_hc_graph", hcp.visualize_hc_graph, hcp.visualize_hc_graph);
164  nh.param("visualize_with_time_as_z_axis_scale", hcp.visualize_with_time_as_z_axis_scale, hcp.visualize_with_time_as_z_axis_scale);
165  nh.param("delete_detours_backwards", hcp.delete_detours_backwards, hcp.delete_detours_backwards);
166  nh.param("detours_orientation_tolerance", hcp.detours_orientation_tolerance, hcp.detours_orientation_tolerance);
167  nh.param("length_start_orientation_vector", hcp.length_start_orientation_vector, hcp.length_start_orientation_vector);
168  nh.param("max_ratio_detours_duration_best_duration", hcp.max_ratio_detours_duration_best_duration, hcp.max_ratio_detours_duration_best_duration);
169 
170  // Recovery
171  nh.param("shrink_horizon_backup", recovery.shrink_horizon_backup, recovery.shrink_horizon_backup);
173  nh.param("oscillation_recovery", recovery.oscillation_recovery, recovery.oscillation_recovery);
174  nh.param("oscillation_v_eps", recovery.oscillation_v_eps, recovery.oscillation_v_eps);
175  nh.param("oscillation_omega_eps", recovery.oscillation_omega_eps, recovery.oscillation_omega_eps);
180 
181  checkParameters();
182  checkDeprecated(nh);
183 }
184 
185 void TebConfig::reconfigure(TebLocalPlannerReconfigureConfig& cfg)
186 {
187  boost::mutex::scoped_lock l(config_mutex_);
188 
189  // Trajectory
190  trajectory.teb_autosize = cfg.teb_autosize;
191  trajectory.dt_ref = cfg.dt_ref;
192  trajectory.dt_hysteresis = cfg.dt_hysteresis;
193  trajectory.global_plan_overwrite_orientation = cfg.global_plan_overwrite_orientation;
194  trajectory.allow_init_with_backwards_motion = cfg.allow_init_with_backwards_motion;
195  trajectory.global_plan_viapoint_sep = cfg.global_plan_viapoint_sep;
196  trajectory.via_points_ordered = cfg.via_points_ordered;
197  trajectory.max_global_plan_lookahead_dist = cfg.max_global_plan_lookahead_dist;
198  trajectory.exact_arc_length = cfg.exact_arc_length;
199  trajectory.force_reinit_new_goal_dist = cfg.force_reinit_new_goal_dist;
200  trajectory.force_reinit_new_goal_angular = cfg.force_reinit_new_goal_angular;
201  trajectory.feasibility_check_no_poses = cfg.feasibility_check_no_poses;
202  trajectory.feasibility_check_lookahead_distance = cfg.feasibility_check_lookahead_distance;
203  trajectory.publish_feedback = cfg.publish_feedback;
204  trajectory.control_look_ahead_poses = cfg.control_look_ahead_poses;
205  trajectory.prevent_look_ahead_poses_near_goal = cfg.prevent_look_ahead_poses_near_goal;
206 
207  // Robot
208  robot.max_vel_x = cfg.max_vel_x;
209  robot.max_vel_x_backwards = cfg.max_vel_x_backwards;
210  robot.max_vel_y = cfg.max_vel_y;
211  robot.max_vel_theta = cfg.max_vel_theta;
212  robot.acc_lim_x = cfg.acc_lim_x;
213  robot.acc_lim_y = cfg.acc_lim_y;
214  robot.acc_lim_theta = cfg.acc_lim_theta;
215  robot.min_turning_radius = cfg.min_turning_radius;
216  robot.wheelbase = cfg.wheelbase;
217  robot.cmd_angle_instead_rotvel = cfg.cmd_angle_instead_rotvel;
218  robot.use_proportional_saturation = cfg.use_proportional_saturation;
219  if (cfg.max_vel_trans == 0.0)
220  {
221  ROS_INFO_STREAM("max_vel_trans is not set, setting it equal to max_vel_x: " << robot.max_vel_x);
222  cfg.max_vel_trans = robot.max_vel_x;
223  }
224  robot.max_vel_trans = cfg.max_vel_trans;
225 
226  // GoalTolerance
227  goal_tolerance.xy_goal_tolerance = cfg.xy_goal_tolerance;
228  goal_tolerance.yaw_goal_tolerance = cfg.yaw_goal_tolerance;
229  goal_tolerance.free_goal_vel = cfg.free_goal_vel;
230  goal_tolerance.trans_stopped_vel = cfg.trans_stopped_vel;
231  goal_tolerance.theta_stopped_vel = cfg.theta_stopped_vel;
232 
233  // Obstacles
234  obstacles.min_obstacle_dist = cfg.min_obstacle_dist;
235  obstacles.inflation_dist = cfg.inflation_dist;
236  obstacles.dynamic_obstacle_inflation_dist = cfg.dynamic_obstacle_inflation_dist;
237  obstacles.include_dynamic_obstacles = cfg.include_dynamic_obstacles;
238  obstacles.include_costmap_obstacles = cfg.include_costmap_obstacles;
239  obstacles.legacy_obstacle_association = cfg.legacy_obstacle_association;
240  obstacles.obstacle_association_force_inclusion_factor = cfg.obstacle_association_force_inclusion_factor;
241  obstacles.obstacle_association_cutoff_factor = cfg.obstacle_association_cutoff_factor;
242  obstacles.costmap_obstacles_behind_robot_dist = cfg.costmap_obstacles_behind_robot_dist;
243  obstacles.obstacle_poses_affected = cfg.obstacle_poses_affected;
244  obstacles.obstacle_proximity_ratio_max_vel = cfg.obstacle_proximity_ratio_max_vel;
245  obstacles.obstacle_proximity_lower_bound = cfg.obstacle_proximity_lower_bound;
246  obstacles.obstacle_proximity_upper_bound = cfg.obstacle_proximity_upper_bound;
247 
248  // Optimization
249  optim.no_inner_iterations = cfg.no_inner_iterations;
250  optim.no_outer_iterations = cfg.no_outer_iterations;
251  optim.optimization_activate = cfg.optimization_activate;
252  optim.optimization_verbose = cfg.optimization_verbose;
253  optim.penalty_epsilon = cfg.penalty_epsilon;
254  optim.weight_max_vel_x = cfg.weight_max_vel_x;
255  optim.weight_max_vel_y = cfg.weight_max_vel_y;
256  optim.weight_max_vel_theta = cfg.weight_max_vel_theta;
257  optim.weight_acc_lim_x = cfg.weight_acc_lim_x;
258  optim.weight_acc_lim_y = cfg.weight_acc_lim_y;
259  optim.weight_acc_lim_theta = cfg.weight_acc_lim_theta;
260  optim.weight_kinematics_nh = cfg.weight_kinematics_nh;
261  optim.weight_kinematics_forward_drive = cfg.weight_kinematics_forward_drive;
262  optim.weight_kinematics_turning_radius = cfg.weight_kinematics_turning_radius;
263  optim.weight_optimaltime = cfg.weight_optimaltime;
264  optim.weight_shortest_path = cfg.weight_shortest_path;
265  optim.weight_obstacle = cfg.weight_obstacle;
266  optim.weight_inflation = cfg.weight_inflation;
267  optim.weight_dynamic_obstacle = cfg.weight_dynamic_obstacle;
268  optim.weight_dynamic_obstacle_inflation = cfg.weight_dynamic_obstacle_inflation;
269  optim.weight_velocity_obstacle_ratio = cfg.weight_velocity_obstacle_ratio;
270  optim.weight_viapoint = cfg.weight_viapoint;
271  optim.weight_adapt_factor = cfg.weight_adapt_factor;
272  optim.obstacle_cost_exponent = cfg.obstacle_cost_exponent;
273 
274  // Homotopy Class Planner
275  hcp.enable_multithreading = cfg.enable_multithreading;
276  hcp.max_number_classes = cfg.max_number_classes;
277  hcp.max_number_plans_in_current_class = cfg.max_number_plans_in_current_class;
278  hcp.selection_cost_hysteresis = cfg.selection_cost_hysteresis;
279  hcp.selection_prefer_initial_plan = cfg.selection_prefer_initial_plan;
280  hcp.selection_obst_cost_scale = cfg.selection_obst_cost_scale;
281  hcp.selection_viapoint_cost_scale = cfg.selection_viapoint_cost_scale;
282  hcp.selection_alternative_time_cost = cfg.selection_alternative_time_cost;
283  hcp.selection_dropping_probability = cfg.selection_dropping_probability;
284  hcp.switching_blocking_period = cfg.switching_blocking_period;
285 
286  hcp.obstacle_heading_threshold = cfg.obstacle_heading_threshold;
287  hcp.roadmap_graph_no_samples = cfg.roadmap_graph_no_samples;
288  hcp.roadmap_graph_area_width = cfg.roadmap_graph_area_width;
289  hcp.roadmap_graph_area_length_scale = cfg.roadmap_graph_area_length_scale;
290  hcp.h_signature_prescaler = cfg.h_signature_prescaler;
291  hcp.h_signature_threshold = cfg.h_signature_threshold;
292  hcp.viapoints_all_candidates = cfg.viapoints_all_candidates;
293  hcp.visualize_hc_graph = cfg.visualize_hc_graph;
294  hcp.visualize_with_time_as_z_axis_scale = cfg.visualize_with_time_as_z_axis_scale;
295 
296  // Recovery
297  recovery.shrink_horizon_backup = cfg.shrink_horizon_backup;
298  recovery.oscillation_recovery = cfg.oscillation_recovery;
299  recovery.divergence_detection_enable = cfg.divergence_detection_enable;
300  recovery.divergence_detection_max_chi_squared = cfg.divergence_detection_max_chi_squared;
301 
302 
303  checkParameters();
304 }
305 
306 
307 void TebConfig::checkParameters() const
308 {
309  // positive backward velocity?
310  if (robot.max_vel_x_backwards <= 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.");
312 
313  // bounds smaller than penalty epsilon
315  ROS_WARN("TebLocalPlannerROS() Param Warning: max_vel_x <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!");
316 
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!");
319 
321  ROS_WARN("TebLocalPlannerROS() Param Warning: max_vel_theta <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!");
322 
324  ROS_WARN("TebLocalPlannerROS() Param Warning: acc_lim_x <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!");
325 
327  ROS_WARN("TebLocalPlannerROS() Param Warning: acc_lim_theta <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!");
328 
329  // dt_ref and dt_hyst
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!");
332 
333  // min number of samples
334  if (trajectory.min_samples <3)
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 ...");
336 
337  // costmap obstacle behind robot
339  ROS_WARN("TebLocalPlannerROS() Param Warning: parameter 'costmap_obstacles_behind_robot_dist' should be positive or zero.");
340 
341  // hcp: obstacle heading threshold
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.");
344 
345  // carlike
347  ROS_WARN("TebLocalPlannerROS() Param Warning: parameter cmd_angle_instead_rotvel is non-zero but wheelbase is set to zero: undesired behavior.");
348 
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");
351 
352  // positive weight_adapt_factor
353  if (optim.weight_adapt_factor < 1.0)
354  ROS_WARN("TebLocalPlannerROS() Param Warning: parameter weight_adapt_factor shoud be >= 1.0");
355 
357  ROS_WARN("TebLocalPlannerROS() Param Warning: parameter oscillation_filter_duration must be >= 0");
358 
359  // weights
360  if (optim.weight_optimaltime <= 0)
361  ROS_WARN("TebLocalPlannerROS() Param Warning: parameter weight_optimaltime shoud be > 0 (even if weight_shortest_path is in use)");
362 
363  // holonomic check
364  if (robot.max_vel_y > 0) {
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.");
367  }
368 
369  if (robot.max_vel_trans > std::max(robot.max_vel_x, robot.max_vel_y)) {
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.");
371  }
372  }
373 
374 }
375 
376 void TebConfig::checkDeprecated(const ros::NodeHandle& nh) const
377 {
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'.");
380 
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'.");
383 
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.");
386 
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.");
389 
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'.");
392 
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.");
395 }
396 
397 } // namespace teb_local_planner
teb_local_planner::TebConfig::Robot::transform_tolerance
double transform_tolerance
Definition: teb_config.h:112
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
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
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
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
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::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::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::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_config.h
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::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
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::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
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
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
ROS_WARN
#define ROS_WARN(...)
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
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
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::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::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
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
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::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::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