1.3、Navigation使用与param配置

<<-------------------------------------------------噶一篇marker一下------------------------------------------------->>

        之前更新了 四、Cartographer单雷达建图  五、2D-lidar+IMU完成cartographer建图(天坑)

后,本来更 + 里程计建图,但是一直没时间,但是既然有了图了,先把导航搞定,后续补更融合里程计建图吧。

        在 三、Navigation源码安装 中有两种安装方式,sudo apt install 安装和源码安装两种,你自己随便选一种即可,不过如果需要改动的话还是建议你源码安装。

一、创建ros-pkg

        Tips:此步也可以放入 三、navigation功能包的src中,创建一个单独的启动文件

        在自己的工作空间的src下执行以下命令:

catkin_create_pkg robot_move roscpp rospy std_msgs move_base

        此时创建了一个单独的src用来专门存放启动move_base的配置文件和launch文件,文件结构如图:(本质上讲单独创建一个src其实多此一笔了,但是我看着舒服,请随意)

         其中我将 urdf 发布的 tf 树单独写了一个文件,跟建图的做了个驱动(个人习惯),rviz 也是同建图单独做了区分,mapping 用来存放 cartographer 建好的图,param用于存放move_base的配置文件。

        使用脚本一次性保存图片请参考 十、Cartographer源码100%安装,rosdep问题100%解决(亲测)---4.4

        使用launch文件保存地图请往下看↓↓↓↓↓↓↓

二、Param文件配置

        Tips:仅供参考

        2.1 costmap_common.yaml

        该文件是 costmap 的公共参数文件,用来加载 local_costmap 的参数,直接上自用文件:

footprint: [[-0.1, -0.1], [-0.1, 0.1], [0.1, 0.1], [0.1, -0.1]] 
#  [[x0, y0], [x1, y1], ... [xn, yn]]  

static_layer:
    enabled: true
    map_topic: map
    unknown_cost_value: -1
    lethal_cost_threshold: 100
    first_map_only: flase
    subscribe_to_updates: flase
    track_unkonwn_space: true
    trinary_costmap: true

obstacle_layer:
    enabled: true
    observation_sources: scan
    scan:
        topic: /scan
        sensor_frame: scan
        data_type: LaserScan
        observation_persistence: 0.0
        expected_update_rate: 0.0
        clearing: true
        marking: true
        max_obstacle_height: 2.0
        min_obstacle_height: 0.0
        obstacle_range: 2.0
        raytrace_range: 3.0
    combunation_method: 1

inflation_layer:
    enabled: true
    cost_scaling_factor: 10.0
    inflation_radius: 0.1

        2.2 local_costmap.yaml

local_costmap:
    global_frame: map 
    robot_base_frame: base_footprint 

    update_frequency: 10.0 
    publish_frequency: 5.0 
    transform_tolerance: 0.5

    rolling_window: true
    width: 4.0
    height: 4.0
    resolution: 0.01
    
    plugins:
    - {name: obstacle_layer,          type: "costmap_2d::ObstacleLayer"}
    - {name: inflation_layer,         type: "costmap_2d::InflationLayer"}

        2.3 global_costmap.yaml

global_costmap:
  global_frame: map 
  robot_base_frame: base_footprint 

  update_frequency: 5.0 
  publish_frequency: 5.0 
  transform_tolerance: 0.5 

  rolling_window: false
  resolutin: 0.02

  plugins: 
    - {name: static_layer,            type: "costmap_2d::StaticLayer"}
    - {name: obstacle_layer,          type: "costmap_2d::VoxelLayer"}
    - {name: inflation_layer,         type: "costmap_2d::InflationLayer"}

         2.4 move_base_planner.yaml

shutdown_costmaps: false 

controller_frequency: 10.0  
controller_patience: 15.0 
 
planner_frequency: 1.0  

planner_patience: 3.0

oscillation_timeout: 10.0 
oscillation_distance: 0.02 
max_planning_retries: 1 

recovery_behavior_enabled: false
clearing_rotation_allowed: false


recovery_behaviors:  # 自恢复行为
  - name: 'conservative_reset'  
    type: 'clear_costmap_recovery/ClearCostmapRecovery'  

  - name: 'clearing_rotation'
    type: 'rotate_recovery/RotateRecovery'  

  - name: 'clearing_move'
    type: 'move_slow_and_clear/MoveSlowAndClear'

conservative_reset:  
  reset_distance: 1.0  
  #layer_names: [static_layer, obstacle_layer, inflation_layer]
  layer_names: [obstacle_layer]  

aggressive_reset:  
  reset_distance: 3.0  
  #layer_names: [static_layer, obstacle_layer, inflation_layer]
  layer_names: [obstacle_layer]

super_reset:  
  reset_distance: 5.0  
  #layer_names: [static_layer, obstacle_layer, inflation_layer]
  layer_names: [obstacle_layer]

move_slow_and_clear:  
  clearing_distance: 0.1
  limited_trans_speed: 0.1  
  limited_rot_speed: 0.4  
  limited_distance: 0.3  

        2.4 base_global_planner.yaml

GlobalPlanner:      
  old_navfn_behavior: false            
  use_quadratic: true
  use_dijkstra: true                
  use_grid_path: false            
  
  allow_unknown:  true
  visralize_potential: flase                 
  publish_potential: true

  default_tolerance: 0.0

  lethal_cosr: 253
  neuthal_cost: 66
  cost_factor: 3.0

  orientation_mode: 0
  orientation_window_size: 1
  outline_map: true

        2.5 teb_local_planner.yaml

        我用的teb,所有dwa就不用了,有需要的可以说。

TebLocalPlannerROS:

 odom_topic: odom
 map_frame: map

 #Trajectory
 teb_autosize: True 
 dt_ref: 0.3 
 dt_hysteresis: 0.03
 global_plan_overwrite_orientation: False 
 #allow_init_with_backwards_motion:False 
 max_global_plan_lookahead_dist: 3.0 
 feasibility_check_no_poses: 5 

 # Robot
 max_vel_x: 0.5 
 max_vel_y: 0.5 
 max_vel_x_backwards: 0.5 
 max_vel_theta: 0.5 
 acc_lim_x: 0.1 
 acc_lim_y: 0.1  
 acc_lim_theta: 0.1 


 wheelbase: 0.0 
 min_turning_radius: 0.0

 cmd_angle_instead_rotvel: False

 footprint_model
  type: "polygon"

  #麦轮
  vertices: [[-0.1, -0.1], [-0.1, 0.1], [0.1, 0.1], [0.1, -0.1]]


 xy_goal_tolerance: 0.1  
 yaw_goal_tolerance: 0.01 
 free_goal_vel: False 
 
 # Obstacles
 min_obstacle_dist: 0.1 
 include_costmap_obstacles: True 
 costmap_obstacles_behind_robot_dist: 1.5  default:1.5  0.0~20.0
 obstacle_poses_affected: 15   
 costmap_converter_plugin: ""
 costmap_converter_spin_thread: True
 costmap_converter_rate: 5
 include_dynamic_obstacles: True 
 dynamic_obstacle_inflation_dist: 0.6 

 # Optimization  
 no_inner_iterations: 5 
 no_outer_iterations: 4  
 optimization_activate: True 
 optimization_verbose: False 
 penalty_epsilon: 0.05
 obstacle_cost_exponent: 4
 weight_max_vel_x: 1  
 weight_max_vel_theta: 1 
 weight_acc_lim_x: 2  
 weight_acc_lim_theta: 1  
 weight_kinematics_nh: 1000
 weight_kinematics_forward_drive: 1
 weight_kinematics_turning_radius: 1 
 weight_optimaltime: 1 # must be > 0 
 weight_shortest_path: 0 
 weight_obstacle: 100
 weight_inflation: 0.2   
 weight_dynamic_obstacle: 10
 weight_dynamic_obstacle_inflation: 0.2  
 weight_viapoint: 1  
 weight_adapt_factor: 2 

 # Homotopy Class Planner
 enable_homotopy_class_planning: False 
 enable_multithreading: True 
 max_number_classes: 5 
 selection_cost_hysteresis: 1.0 
 selection_prefer_initial_plan: 0.95
 selection_obst_cost_scale: 1.0
 selection_alternative_time_cost: False

 roadmap_graph_no_samples: 15
 roadmap_graph_area_width: 5
 roadmap_graph_area_length_scale: 1.0
 h_signature_prescaler: 0.5
 h_signature_threshold: 0.1
 obstacle_heading_threshold: 0.45
 switching_blocking_period: 0.0
 viapoints_all_candidates: True
 delete_detours_backwards: True
 max_ratio_detours_duration_best_duration: 3.0
 visualize_hc_graph: False
 visualize_with_time_as_z_axis_scale: False

 # Recovery
 
 shrink_horizon_backup: True
 shrink_horizon_min_duration: 10
 oscillation_recovery: False 
 oscillation_v_eps: 0.1
 oscillation_omega_eps: 0.1
 oscillation_recovery_min_duration: 10
 oscillation_filter_duration: 10

三、launch文件

        这里只放导航配置部分

<launch>
<master auto="start"/>

    <!-- Run AMCL -->
    <include file="$(find xxxxxx)/launch/amcl.launch" />

    <!--Run move_base node-->
  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />

    <rosparam file="$(find xxxxxx)/param/costmap_common.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find xxxxxx)/param/costmap_common.yaml" command="load" ns="local_costmap" />
    <rosparam file="$(find xxxxxx)/param/local_costmap.yaml" command="load" />
    <rosparam file="$(find xxxxxx)/param/global_costmap.yaml" command="load" />
    <rosparam file="$(find xxxxxx)/param/move_base_planner.yaml" command="load" />

    <rosparam command="load" file="$(find xxxxxx)/param/base_global_planner.yaml" />
    <rosparam command="load" file="$(find xxxxxx)/param/teb_local_planner.yaml" />
  </node>

</launch>

        不积跬步无以至千里,不积小流无以成江河  -----------------------------2:05

  • 2
    点赞
  • 9
    收藏
    觉得还不错? 一键收藏
  • 2
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值