Trajectory related parameters. More...
#include <teb_config.h>
Public Attributes | |
bool | allow_init_with_backwards_motion |
If true, the underlying trajectories might be initialized with backwards motions in case the goal is behind the start within the local costmap (this is only recommended if the robot is equipped with rear sensors) More... | |
int | control_look_ahead_poses |
Min angular resolution used during the costmap collision check. If not respected, intermediate samples are added. [rad]. More... | |
double | dt_hysteresis |
Hysteresis for automatic resizing depending on the current temporal resolution (dt): usually 10% of dt_ref. More... | |
double | dt_ref |
Desired temporal resolution of the trajectory (should be in the magniture of the underlying control rate) More... | |
bool | exact_arc_length |
If true, the planner uses the exact arc length in velocity, acceleration and turning rate computations [-> increased cpu time], otherwise the euclidean approximation is used. More... | |
int | feasibility_check_no_poses |
Specify up to which pose on the predicted plan the feasibility should be checked each sampling interval. More... | |
double | force_reinit_new_goal_angular |
Reinitialize the trajectory if a previous goal is updated with an angular difference of more than the specified value in radians (skip hot-starting) More... | |
double | force_reinit_new_goal_dist |
Reinitialize the trajectory if a previous goal is updated with a seperation of more than the specified value in meters (skip hot-starting) More... | |
bool | global_plan_overwrite_orientation |
Overwrite orientation of local subgoals provided by the global planner. More... | |
double | global_plan_prune_distance |
Distance between robot and via_points of global plan which is used for pruning. More... | |
double | global_plan_viapoint_sep |
Min. separation between each two consecutive via-points extracted from the global plan (if negative: disabled) More... | |
double | max_global_plan_lookahead_dist |
Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into account for optimization [if <=0: disabled; the length is also bounded by the local costmap size!]. More... | |
int | max_samples |
Maximum number of samples; Warning: if too small the discretization/resolution might not be sufficient for the given robot model or obstacle avoidance does not work anymore. More... | |
double | min_resolution_collision_check_angular |
int | min_samples |
Minimum number of samples (should be always greater than 2) More... | |
bool | publish_feedback |
Publish planner feedback containing the full trajectory and a list of active obstacles (should be enabled only for evaluation or debugging purposes) More... | |
double | teb_autosize |
Enable automatic resizing of the trajectory w.r.t to the temporal resolution (recommended) More... | |
bool | via_points_ordered |
If true, the planner adheres to the order of via-points in the storage container. More... | |
Trajectory related parameters.
Definition at line 69 of file teb_config.h.
bool teb_local_planner::TebConfig::Trajectory::allow_init_with_backwards_motion |
If true, the underlying trajectories might be initialized with backwards motions in case the goal is behind the start within the local costmap (this is only recommended if the robot is equipped with rear sensors)
Definition at line 77 of file teb_config.h.
int teb_local_planner::TebConfig::Trajectory::control_look_ahead_poses |
Min angular resolution used during the costmap collision check. If not respected, intermediate samples are added. [rad].
Definition at line 88 of file teb_config.h.
double teb_local_planner::TebConfig::Trajectory::dt_hysteresis |
Hysteresis for automatic resizing depending on the current temporal resolution (dt): usually 10% of dt_ref.
Definition at line 73 of file teb_config.h.
double teb_local_planner::TebConfig::Trajectory::dt_ref |
Desired temporal resolution of the trajectory (should be in the magniture of the underlying control rate)
Definition at line 72 of file teb_config.h.
bool teb_local_planner::TebConfig::Trajectory::exact_arc_length |
If true, the planner uses the exact arc length in velocity, acceleration and turning rate computations [-> increased cpu time], otherwise the euclidean approximation is used.
Definition at line 82 of file teb_config.h.
int teb_local_planner::TebConfig::Trajectory::feasibility_check_no_poses |
Specify up to which pose on the predicted plan the feasibility should be checked each sampling interval.
Definition at line 85 of file teb_config.h.
double teb_local_planner::TebConfig::Trajectory::force_reinit_new_goal_angular |
Reinitialize the trajectory if a previous goal is updated with an angular difference of more than the specified value in radians (skip hot-starting)
Definition at line 84 of file teb_config.h.
double teb_local_planner::TebConfig::Trajectory::force_reinit_new_goal_dist |
Reinitialize the trajectory if a previous goal is updated with a seperation of more than the specified value in meters (skip hot-starting)
Definition at line 83 of file teb_config.h.
bool teb_local_planner::TebConfig::Trajectory::global_plan_overwrite_orientation |
Overwrite orientation of local subgoals provided by the global planner.
Definition at line 76 of file teb_config.h.
double teb_local_planner::TebConfig::Trajectory::global_plan_prune_distance |
Distance between robot and via_points of global plan which is used for pruning.
Definition at line 81 of file teb_config.h.
double teb_local_planner::TebConfig::Trajectory::global_plan_viapoint_sep |
Min. separation between each two consecutive via-points extracted from the global plan (if negative: disabled)
Definition at line 78 of file teb_config.h.
double teb_local_planner::TebConfig::Trajectory::max_global_plan_lookahead_dist |
Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into account for optimization [if <=0: disabled; the length is also bounded by the local costmap size!].
Definition at line 80 of file teb_config.h.
int teb_local_planner::TebConfig::Trajectory::max_samples |
Maximum number of samples; Warning: if too small the discretization/resolution might not be sufficient for the given robot model or obstacle avoidance does not work anymore.
Definition at line 75 of file teb_config.h.
double teb_local_planner::TebConfig::Trajectory::min_resolution_collision_check_angular |
Definition at line 87 of file teb_config.h.
int teb_local_planner::TebConfig::Trajectory::min_samples |
Minimum number of samples (should be always greater than 2)
Definition at line 74 of file teb_config.h.
bool teb_local_planner::TebConfig::Trajectory::publish_feedback |
Publish planner feedback containing the full trajectory and a list of active obstacles (should be enabled only for evaluation or debugging purposes)
Definition at line 86 of file teb_config.h.
double teb_local_planner::TebConfig::Trajectory::teb_autosize |
Enable automatic resizing of the trajectory w.r.t to the temporal resolution (recommended)
Definition at line 71 of file teb_config.h.
bool teb_local_planner::TebConfig::Trajectory::via_points_ordered |
If true, the planner adheres to the order of via-points in the storage container.
Definition at line 79 of file teb_config.h.