ROS - teb_local_planner 参数总结

参考官方教程 http://wiki.ros.org/teb_local_planner/Tutorials, 全英文看着有点累, 在此总结一下调试的过程和小小的经验

安装 teb_local_planner

sudo apt-get install ros-kinetic-teb-local-planner
sudo apt-get install ros-kinetic-teb-local-planner-tutorials

观察单个轨迹的仿真

主要是观察参数对于路径规划上的影响
启动节点 和 rviz

rosparam set /test_optim_node/enable_homotopy_class_planning True
roslaunch teb_local_planner test_optim_node.launch

在这里插入图片描述

启动参数调节器
这里可以观察参数的对于路径规划上的影响.

rosrun rqt_reconfigure rqt_reconfigure

在这里插入图片描述

不同机器人FootPrint 的仿真

两轮差速 机器人的仿真

roslaunch teb_local_planner_tutorials robot_diff_drive_in_stage.launch 

启动参数调节器

rosrun rqt_reconfigure rqt_reconfigure

汽车模型机器人

roslaunch teb_local_planner_tutorials robot_carlike_in_stage.launch 

在这里插入图片描述

TEB 的参数调试

参数类型含义最小默认最大
teb_autosizebool优化期间允许改变轨迹的时域长度;Enable the automatic resizing of the trajectory during optimization (based on the temporal resolution of the trajectory, recommended)FalseTrueTrue
dt_refdouble局部路径规划的解析度; Temporal resolution of the planned trajectory (usually it is set to the magnitude of the 1/control_rate)0.010.31.0
dt_hysteresisdouble允许改变的时域解析度的浮动范围, 一般为 dt_ref 的 10% 左右; Hysteresis that is utilized for automatic resizing depending on the current temporal resolution (dt): usually 10% of dt_ref0.0020.10.5
global_plan_overwrite_orientationbool覆盖全局路径中局部路径点的朝向,Some global planners are not considering the orientation at local subgoals between start and global goal, therefore determine it automaticallyFalseTrueTrue
allow_init_with_backwards_motionbool允许在开始时想后退来执行轨迹,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)FalseFalseTrue
max_global_plan_lookahead_distdouble考虑优化的全局计划子集的最大长度(累积欧几里得距离)(如果为0或负数:禁用;长度也受本地Costmap大小的限制), Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into account for optimization [if 0 or negative: disabled; the length is also bounded by the local costmap size ]0.03.050.0
force_reinit_new_goal_distdouble如果上一个目标的间隔超过指定的米数(跳过热启动),则强制规划器重新初始化轨迹,Force the planner to reinitialize the trajectory if a previous goal is updated with a seperation of more than the specified value in meters (skip hot-starting)0.01.010.0
feasibility_check_no_posesint检测位姿可到达的时间间隔,Specify up to which pose on the predicted plan the feasibility should be checked each sampling interval0550
exact_arc_lengthbool如果为真,规划器在速度、加速度和转弯率计算中使用精确的弧长[->增加的CPU时间],否则使用欧几里德近似。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.FalseFalseTrue
publish_feedbackbool发布包含完整轨迹和活动障碍物列表的规划器反馈,Publish planner feedback containing the full trajectory and a list of active obstacles (should be enabled only for evaluation or debugging purposes)FalseFalseTrue
visualize_with_time_as_z_axis_scaledouble如果该值大于0,则使用该值缩放的Z轴的时间在3D中可视化轨迹和障碍物。最适用于动态障碍。 If this value is bigger than 0, the trajectory and obstacles are visualized in 3d using the time as the z-axis scaled by this value. Most useful for dynamic obstacles.0.00.01.0
global_plan_viapoint_sepdouble从全局计划中提取的每两个连续通过点之间的最小间隔[如果为负:禁用], Min. separation between each two consecutive via-points extracted from the global plan [if negative: disabled]-0.1-0.15.0
via_points_orderedbool如果为真,规划器遵循存储容器中通过点的顺序。If true, the planner adheres to the order of via-points in the storage containerFalseFalseTrue
max_vel_xdouble最大x前向速度,Maximum translational velocity of the robot0.010.4100.0
max_vel_x_backwardsdouble最大x后退速度,Maximum translational velocity of the robot for driving backwards0.010.2100.0
max_vel_thetadouble最大转向叫速度 Maximum angular velocity of the robot0.010.3100.0
acc_lim_xdouble最大x加速度,Maximum translational acceleration of the robot0.010.5100.0
acc_lim_thetadouble最大角速度,Maximum angular acceleration of the robot0.010.5100.0
is_footprint_dynamicbool是否footprint 为动态的,If true, updated the footprint before checking trajectory feasibilityFalseFalseTrue
min_turning_radiusdouble车类机器人的最小转弯半径,Minimum turning radius of a carlike robot (diff-drive robot: zero)0.00.050.0
wheelbasedouble驱动轴和转向轴之间的距离(仅适用于启用了“Cmd_angle_而不是_rotvel”的Carlike机器人);对于后轮式机器人,该值可能为负值! The distance between the drive shaft and steering axle (only required for a carlike robot with ‘cmd_angle_instead_rotvel’ enabled); The value might be negative for back-wheeled robots!-10.01.010.0
cmd_angle_instead_rotvelbool将收到的角速度消息转换为 操作上的角度变化。 Substitute the rotational velocity in the commanded velocity message by the corresponding steering angle (check ‘axles_distance’)FalseFalseTrue
max_vel_ydouble最大y方向速度, Maximum strafing velocity of the robot (should be zero for non-holonomic robots!)0.00.0100.0
acc_lim_ydouble最大y向加速度, Maximum strafing acceleration of the robot0.010.5100.0
xy_goal_tolerancedouble目标 xy 偏移容忍度,Allowed final euclidean distance to the goal position0.0010.210.0
yaw_goal_tolerancedouble目标 角度 偏移容忍度, Allowed final orientation error to the goal orientation0.0010.13.2
free_goal_velbool允许机器人以最大速度驶向目的地, Allow the robot’s velocity to be nonzero for planning purposes (the robot can arrive at the goal with max speed)FalseFalseTrue
min_obstacle_distdouble和障碍物最小距离, Minimum desired separation from obstacles0.00.510.0
inflation_distdouble障碍物膨胀距离, Buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect)0.00.615.0
dynamic_obstacle_inflation_distdouble动态障碍物的膨胀范围, Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect)0.00.615.0
include_dynamic_obstaclesbool是否将动态障碍物预测为速度模型, Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (this also changes the homotopy class search). If false, all obstacles are considered to be static.FalseFalseTrue
include_costmap_obstaclesboolcostmap 中的障碍物是否被直接考虑, Specify whether the obstacles in the costmap should be taken into account directly (this is necessary if no seperate clustering and detection is implemented)FalseTrueTrue
legacy_obstacle_associationbool是否严格遵循局部规划出来的路径, If true, the old association strategy is used (for each obstacle, find the nearest TEB pose), otherwise the new one (for each teb pose, find only ‘relevant’ obstacles).FalseFalseTrue
obstacle_association_force_inclusion_factordoubleThe non-legacy obstacle association technique tries to connect only relevant obstacles with the discretized trajectory during optimization, all obstacles within a specifed distance are forced to be included (as a multiple of min_obstacle_dist), e.g. choose 2.0 in order to consider obstacles within a radius of 2.0*min_obstacle_dist.0.01.5100.0
obstacle_association_cutoff_factordoubleSee obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist all obstacles are ignored during optimization. obstacle_association_force_inclusion_factor is processed first.1.05.0100.0
costmap_obstacles_behind_robot_distdoubleLimit the occupied local costmap obstacles taken into account for planning behind the robot (specify distance in meters)0.01.520.0
obstacle_poses_affectedintThe obstacle position is attached to the closest pose on the trajectory to reduce computational effort, but take a number of neighbors into account as well030200
no_inner_iterationsint被外循环调用后内循环执行优化次数, Number of solver iterations called in each outerloop iteration15100
no_outer_iterationsint执行的外循环的优化次数, Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with no_inner_iterations14100
optimization_activatebool激活优化, Activate the optimizationFalseTrueTrue
optimization_verbosebool打印优化过程详情, Print verbose informationFalseFalseTrue
penalty_epsilondouble对于硬约束近似,在惩罚函数中添加安全范围, Add a small safty margin to penalty functions for hard-constraint approximations0.00.11.0
weight_max_vel_xdouble最大x速度权重, Optimization weight for satisfying the maximum allowed translational velocity0.02.01000.0
weight_max_vel_ydouble最大y速度权重,Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic robots)0.02.01000.0
weight_max_vel_thetadouble最大叫速度权重, Optimization weight for satisfying the maximum allowed angular velocity0.01.01000.0
weight_acc_lim_xdouble最大x 加速度权重,Optimization weight for satisfying the maximum allowed translational acceleration0.01.01000.0
weight_acc_lim_ydouble最大y 加速度权重,Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonomic robots)0.01.01000.0
weight_acc_lim_thetadouble最大角速度权重,Optimization weight for satisfying the maximum allowed angular acceleration0.01.01000.0
weight_kinematics_nhdoubleOptimization weight for satisfying the non-holonomic kinematics0.01000.010000.0
weight_kinematics_forward_drivedouble优化过程中,迫使机器人只选择前进方向,差速轮适用,Optimization weight for forcing the robot to choose only forward directions (positive transl. velocities, only diffdrive robot)0.01.01000.0
weight_kinematics_turning_radiusdouble优化过程中,车型机器人的最小转弯半径的权重。 Optimization weight for enforcing a minimum turning radius (carlike robots)0.01.01000.0
weight_optimaltimedouble优化过程中,基于轨迹的时间上的权重, Optimization weight for contracting the trajectory w.r.t transition time0.01.01000.0
weight_obstacledouble优化过程中,和障碍物最小距离的权重,Optimization weight for satisfying a minimum seperation from obstacles0.050.01000.0
weight_inflationdouble优化过程中, 膨胀区的权重,Optimization weight for the inflation penalty (should be small)0.00.110.0
weight_dynamic_obstacledouble优化过程中,和动态障碍物最小距离的权重,Optimization weight for satisfying a minimum seperation from dynamic obstacles0.050.01000.0
weight_dynamic_obstacle_inflationdouble优化过程中,和动态障碍物膨胀区的权重,Optimization weight for the inflation penalty of dynamic obstacles (should be small)0.00.110.0
weight_viapointdouble优化过程中,和全局路径采样点距离的权重, Optimization weight for minimizing the distance to via-points0.01.01000.0
weight_adapt_factordoubleSome special weights (currently ‘weight_obstacle’) are repeatedly scaled by this factor in each outer TEB iteration (weight_new: weight_old * factor); Increasing weights iteratively instead of setting a huge value a-priori leads to better numerical conditions of the underlying optimization problem.1.02.0100.0
enable_multithreadingbool允许多线程并行处理, Activate multiple threading for planning multiple trajectories in parallelFalseTrueTrue
max_number_classesint允许的线程数, Specify the maximum number of allowed alternative homotopy classes (limits computational effort)15100
selection_cost_hysteresisdoubleSpecify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in order to be selected (selection if new_cost < old_cost*factor)0.01.02.0
selection_prefer_initial_plandoubleSpecify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the initial plan.)0.00.951.0
selection_obst_cost_scaledoubleExtra scaling of obstacle cost terms just for selecting the ‘best’ candidate (new_obst_cost: obst_cost*factor)0.0100.01000.0
selection_viapoint_cost_scaledoubleExtra scaling of via-point cost terms just for selecting the ‘best’ candidate. (new_viapt_cost: viapt_cost*factor)0.01.0100.0
selection_alternative_time_costboolIf true, time cost is replaced by the total transition time.FalseFalseTrue
switching_blocking_perioddoubleSpecify a time duration in seconds that needs to be expired before a switch to new equivalence class is allowed0.00.060.0
roadmap_graph_no_samplesintSpecify the number of samples generated for creating the roadmap graph, if simple_exploration is turend off115100
roadmap_graph_area_widthdoubleSpecify the width of the area in which sampled will be generated between start and goal [m ] (the height equals the start-goal distance)0.15.020.0
roadmap_graph_area_length_scaledoubleThe length of the rectangular region is determined by the distance between start and goal. This parameter further scales the distance such that the geometric center remains equal!)0.51.02.0
h_signature_prescalerdoubleScale number of obstacle value in order to allow huge number of obstacles. Do not choose it extremly low, otherwise obstacles cannot be distinguished from each other (0.2<H<=1)0.21.01.0
h_signature_thresholddoubleTwo h-signuteres are assumed to be equal, if both the difference of real parts and complex parts are below the specified threshold0.00.11.0
obstacle_heading_thresholddoubleSpecify the value of the normalized scalar product between obstacle heading and goal heading in order to take them (obstacles) into account for exploration)0.00.451.0
viapoints_all_candidatesboolIf true, all trajectories of different topologies are attached to the set of via-points, otherwise only the trajectory sharing the same one as the initial/global plan is attached (no effect in test_optim_node).FalseTrueTrue
visualize_hc_graphboolVisualize the graph that is created for exploring new homotopy classesFalseFalseTrue
shrink_horizon_backupbool当规划器检测到系统异常,允许缩小时域规划范围。Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues.FalseTrueTrue
oscillation_recoverybool尝试检测和解决振荡,Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robot frequently switches between left/right/forward/backwards).FalseTrueTrue

重要参数总结

序号参数功能
1max_global_plan_lookahead_dist考虑优化的全局计划子集的最大长度(累积欧几里得距离)
2min_obstacle_dist避障距离(障碍物膨胀半径)
3dt_ref轨迹的时间分辨率, TEB 时间最优策略, 分辨率越高更好逼近真实
  • 73
    点赞
  • 526
    收藏
    觉得还不错? 一键收藏
  • 6
    评论
### 回答1: teb_local_plannerROS中常用的局部路径规划器,其调参需要考虑多个参数。以下是teb_local_planner调参攻略: 1. 调整teb_local_planner的全局参数,包括机器人的最大速度、最大加速度、最大角速度等。这些参数需要根据机器人的实际情况进行调整。 2. 调整teb_local_planner的局部参数,包括机器人的最小转弯半径、最小速度、最大速度等。这些参数需要根据机器人的轮廓和环境的限制进行调整。 3. 调整teb_local_planner的代价函数参数,包括机器人与障碍物的距离、机器人的速度、机器人的加速度等。这些参数需要根据机器人的实际情况和环境的限制进行调整。 4. 调整teb_local_planner的优化器参数,包括优化器的最大迭代次数、优化器的收敛阈值等。这些参数需要根据机器人的实际情况和环境的限制进行调整。 5. 调整teb_local_planner的路径平滑参数,包括路径平滑的权重、路径平滑的次数等。这些参数需要根据机器人的实际情况和环境的限制进行调整。 总之,teb_local_planner的调参需要根据机器人的实际情况和环境的限制进行调整,需要进行多次实验和调整才能得到最优的参数组合。 ### 回答2: Teb_local_planner是一种ROS中的本地路径规划器,适合机器人在复杂环境中移动。通过对Teb_local_planner进行调参,能够优化机器人的移动路径,提高机器人的机动性和精度。以下是Teb_local_planner调参攻略。 1. 运动速度限制参数:max_vel_x和max_vel_theta max_vel_x指机器人的最大直线运动速度,max_vel_theta指机器人的最大旋转速度。在进行调参时,需要首先调整这两个参数。过高的速度可能导致路径跳跃,过低的速度可能导致机器人移动过慢。在进行调整时,需要考虑到机器人的动力学特性和环境的复杂程度。 2. 运动速度控制参数:vx_samples和theta_samples vx_samples指机器人在执行直线运动时采样的次数,theta_samples指机器人在执行旋转运动时采样的次数。在进行调参时,可以通过增加采样次数来提高机器人的运动精度,但也会带来额外的计算成本。 3. 运动规划边界参数:padding_x和padding_y padding_x指机器人的x轴方向的安全间隔,padding_y指机器人的y轴方向的安全间隔。在进行调参时,需要根据机器人的实际大小以及运动的环境复杂程度来设置这两个参数,以确保机器人的安全移动。 4. 转向惯量参数:robot_inertia robot_inertia指机器人的转向惯量,是影响机器人旋转控制的重要参数。在进行调参时,需要根据机器人的实际转向特性来设置这个参数,以提高机器人的旋转控制精度。 5. 其他参数 还有许多其他的参数可以设置,如路径距离权重参数,控制成本衰减系数等等。在进行调参时,需要考虑整个系统的稳定性和运行速度,同时需要不断改善机器人的安全性和控制精度。 需要注意的是,Teb_local_planner的调参要求对机器人的动力学模型、环境特性和运动控制原理有一定的了解。在调参时需要进行多次实验来不断调整参数,最终得到最优的调参结果。 ### 回答3: teb_local_planner是一种常用的ROS导航中的本地路径规划器,它可以在机器人移动时计算局部路径,并执行转弯动作,以避免障碍物。但是在实际应用中,为使机器人的运动更加平稳稳定,需要对teb_local_planner进行有效的调参。 首先,我们来了解一下teb_local_planner的几个重要的参数:xy_goal_tolerance(目标点的x、y方向误差容许值)、yaw_goal_tolerance(目标点的偏航角误差容许范围)、max_vel_x(机器人最大线速度)、min_vel_x(机器人最小线速度)等。这些参数在调参过程中都需要进行优化,以便更好地适应实际环境。 接着,我们需要根据具体的场景情况进行调参。例如,如果机器人在室内走动,那么应该适当增加xy_goal_tolerance,减小yaw_goal_tolerance,从而提高路径规划的精度,防止机器人的路径跑偏。如果机器人在室外移动,需要考虑风力对移动的影响,可以适当降低机器人的最大线速度和最小线速度,以保证运动的稳定性。 在进行调参操作时,需要通过实际操作实现逐步优化。可以通过rosrun命令来调用teb_local_planner,更改参数,然后观察机器人的移动情况,通过多次测试,得出最佳的参数组合。同时,由于teb_local_planner是为符合人体工程学的曲线形态的移动模式,因此在选择参数时要充分考虑到机器人的形态、重心等因素。 总的来说,teb_local_planner的调参是一个需要持续观察和调整的过程,需要详细的实际测试和参数逐步调优。如果调参不当,会出现机器人的路径精度不高、运动不流畅等问题。因此,我们需要在实际应用中认真调参,以提高机器人的移动效率和精度。
评论 6
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值