45 #include <Eigen/StdVector> 47 #include <teb_local_planner/TebLocalPlannerReconfigureConfig.h> 51 #define USE_ANALYTIC_JACOBI // if available for a specific edge, use analytic jacobi 376 void reconfigure(TebLocalPlannerReconfigureConfig& cfg);
boost::mutex config_mutex_
Mutex for config accesses and changes.
bool include_costmap_obstacles
Specify whether the obstacles in the costmap should be taken into account directly.
bool cmd_angle_instead_rotvel
Substitute the rotational velocity in the commanded velocity message by the corresponding steering an...
std::string map_frame
Global planning frame.
double max_vel_y
Maximum strafing velocity of the robot (should be zero for non-holonomic robots!) ...
int max_samples
Maximum number of samples; Warning: if too small the discretization/resolution might not be sufficien...
double weight_adapt_factor
Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer...
bool allow_init_with_backwards_motion
If true, the underlying trajectories might be initialized with backwards motions in case the goal is ...
double acc_lim_x
Maximum translational acceleration of the robot.
double min_obstacle_dist
Minimum desired separation from obstacles.
double weight_prefer_rotdir
Optimization weight for preferring a specific turning direction (-> currently only activated if an os...
bool shrink_horizon_backup
Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues...
double force_reinit_new_goal_angular
Reinitialize the trajectory if a previous goal is updated with an angular difference of more than the...
int roadmap_graph_no_samples
double roadmap_graph_area_width
< Specify the number of samples generated for creating the roadmap graph, if simple_exploration is tu...
double dt_hysteresis
Hysteresis for automatic resizing depending on the current temporal resolution (dt): usually 10% of d...
Config class for the teb_local_planner and its components.
double weight_max_vel_theta
Optimization weight for satisfying the maximum allowed angular velocity.
bool selection_alternative_time_cost
If true, time cost is replaced by the total transition time.
double xy_goal_tolerance
Allowed final euclidean distance to the goal position.
double global_plan_viapoint_sep
Min. separation between each two consecutive via-points extracted from the global plan (if negative: ...
double obstacle_heading_threshold
Specify the value of the normalized scalar product between obstacle heading and goal heading in order...
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
Recovery/backup related parameters.
double yaw_goal_tolerance
Allowed final orientation error.
double min_turning_radius
Minimum turning radius of a carlike robot (diff-drive robot: zero);.
void checkDeprecated(const ros::NodeHandle &nh) const
Check if some deprecated parameters are found and print warnings.
double detours_orientation_tolerance
A plan is considered a detour if its start orientation differs more than this from the best plan...
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
double weight_max_vel_y
Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic r...
Goal tolerance related parameters.
double weight_kinematics_turning_radius
Optimization weight for enforcing a minimum turning radius (carlike robots)
bool legacy_obstacle_association
If true, the old association strategy is used (for each obstacle, find the nearest TEB pose)...
double weight_acc_lim_x
Optimization weight for satisfying the maximum allowed translational acceleration.
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...
double weight_acc_lim_y
Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonom...
bool optimization_activate
Activate the optimization.
int feasibility_check_no_poses
Specify up to which pose on the predicted plan the feasibility should be checked each sampling interv...
double costmap_obstacles_behind_robot_dist
Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify ...
struct teb_local_planner::TebConfig::GoalTolerance goal_tolerance
Goal tolerance related parameters.
double teb_autosize
Enable automatic resizing of the trajectory w.r.t to the temporal resolution (recommended) ...
Obstacle related parameters.
bool via_points_ordered
If true, the planner adheres to the order of via-points in the storage container. ...
double obstacle_association_force_inclusion_factor
The non-legacy obstacle association technique tries to connect only relevant obstacles with the discr...
void reconfigure(TebLocalPlannerReconfigureConfig &cfg)
Reconfigure parameters from the dynamic_reconfigure config. Change parameters dynamically (e...
double weight_max_vel_x
Optimization weight for satisfying the maximum allowed translational velocity.
double force_reinit_new_goal_dist
Reinitialize the trajectory if a previous goal is updated with a seperation of more than the specifie...
double dt_ref
Desired temporal resolution of the trajectory (should be in the magniture of the underlying control r...
double acc_lim_theta
Maximum angular acceleration of the robot.
bool enable_multithreading
Activate multiple threading for planning multiple trajectories in parallel.
Robot related parameters.
double min_resolution_collision_check_angular
void loadRosParamFromNodeHandle(const ros::NodeHandle &nh)
Load parmeters from the ros param server.
double switching_blocking_period
Specify a time duration in seconds that needs to be expired before a switch to new equivalence class ...
struct teb_local_planner::TebConfig::HomotopyClasses hcp
std::string odom_topic
Topic name of the odometry message, provided by the robot driver or simulator.
double weight_inflation
Optimization weight for the inflation penalty (should be small)
bool visualize_hc_graph
Visualize the graph that is created for exploring new homotopy classes.
bool simple_exploration
If true, distinctive trajectories are explored using a simple left-right approach (pass each obstacle...
int control_look_ahead_poses
Min angular resolution used during the costmap collision check. If not respected, intermediate sample...
double h_signature_prescaler
Scale number of obstacle value in order to allow huge number of obstacles. Do not choose it extremly ...
double selection_cost_hysteresis
Specify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in...
double weight_obstacle
Optimization weight for satisfying a minimum separation from obstacles.
bool delete_detours_backwards
If enabled, the planner will discard the plans detouring backwards with respect to the best plan...
bool enable_homotopy_class_planning
Activate homotopy class planning (Requires much more resources that simple planning, since multiple trajectories are optimized at once).
bool free_goal_vel
Allow the robot's velocity to be nonzero (usally max_vel) for planning purposes.
double max_vel_theta
Maximum angular velocity of the robot.
double oscillation_v_eps
Threshold for the average normalized linear velocity: if oscillation_v_eps and oscillation_omega_eps ...
double penalty_epsilon
Add a small safety margin to penalty functions for hard-constraint approximations.
double length_start_orientation_vector
Length of the vector used to compute the start orientation of a plan.
void checkParameters() const
Check parameters and print warnings in case of discrepancies.
bool exact_arc_length
If true, the planner uses the exact arc length in velocity, acceleration and turning rate computation...
double oscillation_filter_duration
Filter length/duration [sec] for the detection of oscillations.
double obstacle_association_cutoff_factor
See obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist a...
double selection_viapoint_cost_scale
Extra scaling of via-point cost terms just for selecting the 'best' candidate.
bool is_footprint_dynamic
int no_inner_iterations
Number of solver iterations called in each outerloop iteration.
double weight_acc_lim_theta
Optimization weight for satisfying the maximum allowed angular acceleration.
double weight_shortest_path
Optimization weight for contracting the trajectory w.r.t. path length.
double weight_dynamic_obstacle_inflation
Optimization weight for the inflation penalty of dynamic obstacles (should be small) ...
double shrink_horizon_min_duration
Specify minimum duration for the reduced horizon in case an infeasible trajectory is detected...
bool costmap_converter_spin_thread
If true, the costmap converter invokes its callback queue in a different thread.
int obstacle_poses_affected
The obstacle position is attached to the closest pose on the trajectory to reduce computational effor...
double obstacle_keypoint_offset
If simple_exploration is turned on, this parameter determines the distance on the left and right side...
double weight_dynamic_obstacle
Optimization weight for satisfying a minimum separation from dynamic obstacles.
double obstacle_cost_exponent
Exponent for nonlinear obstacle cost (cost = linear_cost * obstacle_cost_exponent). Set to 1 to disable nonlinear cost (default)
Optimization related parameters.
double roadmap_graph_area_length_scale
The length of the rectangular region is determined by the distance between start and goal...
std::string costmap_converter_plugin
Define a plugin name of the costmap_converter package (costmap cells are converted to points/lines/po...
bool viapoints_all_candidates
If true, all trajectories of different topologies are attached to the current set of via-points...
double weight_optimaltime
Optimization weight for contracting the trajectory w.r.t. transition time.
bool global_plan_overwrite_orientation
Overwrite orientation of local subgoals provided by the global planner.
double weight_kinematics_nh
Optimization weight for satisfying the non-holonomic kinematics.
struct teb_local_planner::TebConfig::Recovery recovery
Parameters related to recovery and backup strategies.
TebConfig()
Construct the TebConfig using default values.
int costmap_converter_rate
The rate that defines how often the costmap_converter plugin processes the current costmap (the value...
bool include_dynamic_obstacles
Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (t...
double global_plan_prune_distance
Distance between robot and via_points of global plan which is used for pruning.
double max_vel_x_backwards
Maximum translational velocity of the robot for driving backwards.
double weight_viapoint
Optimization weight for minimizing the distance to via-points.
double oscillation_recovery_min_duration
Minumum duration [sec] for which the recovery mode is activated after an oscillation is detected...
bool complete_global_plan
int no_outer_iterations
Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with...
double dynamic_obstacle_inflation_dist
Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be la...
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
double selection_obst_cost_scale
Extra scaling of obstacle cost terms just for selecting the 'best' candidate.
bool publish_feedback
Publish planner feedback containing the full trajectory and a list of active obstacles (should be ena...
double acc_lim_y
Maximum strafing acceleration of the robot.
double h_signature_threshold
Two h-signatures are assumed to be equal, if both the difference of real parts and complex parts are ...
double oscillation_omega_eps
Threshold for the average normalized angular velocity: if oscillation_v_eps and oscillation_omega_eps...
double wheelbase
The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_a...
double max_global_plan_lookahead_dist
Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into a...
bool oscillation_recovery
Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robo...
int max_number_classes
Specify the maximum number of allowed alternative homotopy classes (limits computational effort) ...
double inflation_dist
buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in ...
double max_ratio_detours_duration_best_duration
Detours are discarted if their execution time / the execution time of the best teb is > this...
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
double weight_kinematics_forward_drive
Optimization weight for forcing the robot to choose only forward directions (positive transl...
int min_samples
Minimum number of samples (should be always greater than 2)
boost::mutex & configMutex()
Return the internal config mutex.
double max_vel_x
Maximum translational velocity of the robot.
bool optimization_verbose
Print verbose information.
Trajectory related parameters.
double selection_prefer_initial_plan
Specify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the ini...