TebLocalPlannerROS:odom_topic:/odom#odom_topic: /rtabmap/odommap_frame:map# Trajectoryteb_autosize:Truedt_ref:0.3#0.2dt_hysteresis:0.1global_plan_overwrite_orientation:Truemax_global_plan_lookahead_dist:3.0feasibility_check_no_poses:5# Robotmax_vel_x:0.40#0.25 max_vel_x_backwards:0.4#0.2max_vel_theta:1.0#0.5acc_lim_x:0.5# 0.2acc_lim_theta:0.6283#0.5, 0.26min_turning_radius:0.0footprint_model:# types: "point", "circular", "two_circles", "line", "polygon"type:"polygon"#"circular" radius:0.38# for type "circular"#line_start: [-0.3, 0.0] # for type "line"#line_end: [0.3, 0.0] # for type "line"#front_offset: 0.2 # for type "two_circles"#front_radius: 0.2 # for type "two_circles"#rear_offset: 0.2 # for type "two_circles"#rear_radius: 0.2 # for type "two_circles"vertices: [ [0.26,0.26], [0.26,-0.26], [-0.26,-0.26], [-0.26,0.26] ] # for type "polygon"# GoalTolerancexy_goal_tolerance:0.2#0.2yaw_goal_tolerance:0.1571free_goal_vel:False# Obstaclesmin_obstacle_dist:0.05inflation_dist:0.0dynamic_obstacle_inflation_dist:0.05include_costmap_obstacles:Truecostmap_obstacles_behind_robot_dist:0.1obstacle_poses_affected:25#30costmap_converter_plugin:""costmap_converter_spin_thread:Truecostmap_converter_rate:5# Optimizationno_inner_iterations:5#5no_outer_iterations:4#4optimization_activate:Trueoptimization_verbose:Falsepenalty_epsilon:0.1weight_max_vel_x:2#2weight_max_vel_theta:1#1weight_acc_lim_x:1# 1weight_acc_lim_theta:1# 1weight_kinematics_nh:1000#1000weight_kinematics_forward_drive:1000#1000weight_kinematics_turning_radius:1#1 #only for car-like robotsweight_optimaltime:1.0#1weight_obstacle:50#50weight_viapoint:5.0#5.0 #1.0weight_inflation:0.1#0.1weight_dynamic_obstacle:10# not in use yetselection_alternative_time_cost:False# not in use yet# Homotopy Class Plannerenable_homotopy_class_planning:False#Trueenable_multithreading:Truesimple_exploration:Falsemax_number_classes:2#4roadmap_graph_no_samples:15roadmap_graph_area_width:5h_signature_prescaler:0.5h_signature_threshold:0.1obstacle_keypoint_offset:0.1obstacle_heading_threshold:0.45visualize_hc_graph:False#ViaPointsglobal_plan_viapoint_sep:0.5#negative if nonevia_points_ordered:False#adhere to order of via points#Feedbackpublish_feedback:true#false
footprint_model:# types: "point", "circular", "two_circles", "line", "polygon"type:"polygon"#"circular" radius:0.38# for type "circular"#line_start: [-0.3, 0.0] # for type "line"#line_end: [0.3, 0.0] # for type "line"#front_offset: 0.2 # for type "two_circles"#front_radius: 0.2 # for type "two_circles"#rear_offset: 0.2 # for type "two_circles"#rear_radius: 0.2 # for type "two_circles"vertices: [ [0.26,0.26], [0.26,-0.26], [-0.26,-0.26], [-0.26,0.26] ] # for type "polygon"
footprint: [ [0.26,0.26], [0.26,-0.26], [-0.26,-0.26], [-0.26,0.26] ]# robot_radius: 0.38 #0.38 # footprint_padding: 0.05 map_type:voxel#track_unknown_space: trueobstacle_layer:origin_z:-0.1z_resolution:1.8#1.5 This must be higher than the z coordinate of the mounted lidarz_voxels:1obstacle_range:10.0#10.0raytrace_range:15.0#15.0observation_sources:laser_scan_sensortrack_unknown_space:truelethal_cost_threshold:100unknown_cost_value:255 laser_scan_sensor: {data_type: LaserScan, topic: /scan, marking: true, clearing: true, min_obstacle_height: 0.00, max_obstacle_height: 3.00}
#point_cloud_sensor: {sensor_frame: lslidar_c16_frame, data_type: PointCloud2, topic: /lslidar_c16/lslidar_point_cloud, marking: true, clearing: true}
lowbstacle_layer:origin_z:-0.1z_resolution:1.8z_voxels:1obstacle_range:3.5#if beyond this threshold, then will not mark as obstacleraytrace_range:5.0#5.0 Lower this value to detect nearer obstacles with better accuracyobservation_sources:obs_cloud mock_scan#butt_scan1 butt_scan2publish_voxel_map:truetrack_unknown_space:truelethal_cost_threshold:100unknown_cost_value:255obs_cloud:data_type:PointCloud2topic:/obstacles_cloudmarking:trueclearing:truemin_obstacle_height:0.01max_obstacle_height:0.99mock_scan:data_type:LaserScantopic:/obstacles_scanmarking:falseclearing:truemin_obstacle_height:0.00max_obstacle_height:1.00inf_is_valid:trueinflation_layer:enabled:truecost_scaling_factor:6.0#added in by Johninflation_radius:0.39#0.45 #Minimum value: 0.379dynamic_obstacle_layer:enabled:falsemap_tolerance:0.2footprint_radius:0.5range:2.0
The inflation_radius is actually the radius to which the cost scaling function is applied, not a parameter of the cost scaling function. Inside the inflation radius, the cost scaling function is applied, but outside the inflation radius, the cost of a cell is not inflated using the cost function.
You'll have to make sure to set the inflation radius large enough that it includes the distance you need the cost function to be applied out to, as anything outside the inflation_radius will not have the cost function applied.
For the correct cost_scaling_factor, solve the equation there ( exp(-1.0 * cost_scaling_factor * (distance_from_obstacle - inscribed_radius)) * (costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1)), using your distance from obstacle and the cost value you want that cell to have.
理想情況下,我們希望設置這兩個參數,使膨脹層幾乎覆蓋走廊,機器人在障礙物之間的中心移動。
(請見下圖)
4.2. 障礙物層Obstacle Layer
障礙層在代價地圖上標出障礙物,它會追蹤感測器數據記錄的障礙物。
obstacle_layer:origin_z:-0.1z_resolution:1.8#1.5 This must be higher than the z coordinate of the mounted lidarz_voxels:1obstacle_range:10.0#10.0raytrace_range:15.0#15.0observation_sources:laser_scan_sensortrack_unknown_space:truelethal_cost_threshold:100unknown_cost_value:255 laser_scan_sensor: {data_type: LaserScan, topic: /scan, marking: true, clearing: true, min_obstacle_height: 0.00, max_obstacle_height: 3.00}
#point_cloud_sensor: {sensor_frame: lslidar_c16_frame, data_type: PointCloud2, topic: /lslidar_c16/lslidar_point_cloud, marking: true, clearing: true}
體素是在空間中具有相對位置的 3D 立方體,可用於深度相機的 3D 重建,如果您不使用 3D,請忽略以下參數。更多相關訊息,請點擊連結 here
origin_z 是地圖的 z 原點(米)。
z_resolution是立方體的高度。
z_resolution controls how dense the voxels is on the z-axis. If it is higher, the voxel layers are denser. If the value is too low (e.g. 0.01), you won’t get useful costmap information. If you set z resolution to a higher value, your intention should be to obtain obstacles better, therefore you need to increase z_voxels parameter which controls how many voxels in each vertical column. It is also useless if you have too many voxels in a column but not enough resolution, because each vertical column has a limit in height.
lowbstacle_layer:origin_z:-0.1z_resolution:1.8z_voxels:1obstacle_range:3.5#if beyond this threshold, then will not mark as obstacleraytrace_range:5.0#5.0 Lower this value to detect nearer obstacles with better accuracyobservation_sources:obs_cloud mock_scan#butt_scan1 butt_scan2publish_voxel_map:truetrack_unknown_space:truelethal_cost_threshold:100unknown_cost_value:255obs_cloud:data_type:PointCloud2topic:/obstacles_cloudmarking:trueclearing:truemin_obstacle_height:0.01max_obstacle_height:0.99mock_scan:data_type:LaserScantopic:/obstacles_scanmarking:falseclearing:truemin_obstacle_height:0.00max_obstacle_height:1.00inf_is_valid:true