move_bae参数介绍

1、move_bae框架

参考:http://wiki.ros.org/move_base

1.主体介绍:

move_base是ROS下关于机器人路径规划的中心枢纽。

它通过订阅激光雷达、map地图、amcl的定位等数据,然后规划出全局和局部路径,再将路径转化为机器人的速度信息,最终实现机器人导航。

首先左上角的amcl左上角的amcl模块是ROS的导航定位模块,amcl也叫自适应蒙特卡罗定位,amcl通过订阅scan、map和tf信息,发布出机器人的pose,以供move_base使用。

左下角odom,即机器人里程计信息。

右上角,map,顾名思义,我们需要的先验地图信息,一般通过slam建图后保存,map_server包通过解析slam建好的地图并发布出去。

右下角的传感器topic则在局部路径规划时起到作用,这部分就是costmap包起到的作用了,costmap为代价地图,目前主要的有inflation_layer、obstacle_layer、static_layer、voxel_layer四个plugins,分别为膨胀层、障碍物层、静态层和体素层。一般我们的全局路径需要静态层和膨胀层,因为全局规划应该只考虑到地图信息,所以一般都是静态的,而局部路径规划则需要考虑到实时的障碍物信息,所以需要障碍物层和膨胀层,

2.构成

它由如下三部分构成:

  • 实现一个actionlib,用于设定目标位置。
  • 连接global planer和local planner,用于实现导航。可以通过重新实现nav_core::BaseGlobalPlanner 和 nav_core::BaseLocalPlanner 的接口,修改global planer和local planner的导航策略
  • 维护两个two costmaps,一个为global planer,另一个为local planner
  • recovery_behaviors: 如果找不到一条到达目标的路径,它就会运行一些清理机制,把地图中一些无效障碍物清理掉,重新制定路径。recovery_behaviors默认策略:

recovery_behaviors默认策略:

2、move_base参数

1. costmap_common_params.yaml

max_obstacle_height: 5.0  # assume something like an arm is mounted on top of the robot
# Obstacle Cost Shaping (http://wiki.ros.org/costmap_2d/hydro/inflation)
robot_radius: 0.20  # 机器人底盘形状,圆形使用robot_radius,非圆形使用footprint(kobuki: 0.18)
# footprint: [[x0, y0], [x1, y1], ... [xn, yn]]  # if the robot is not circular

map_type: voxel

obstacle_layer:
  enabled:              true
  max_obstacle_height:  0.6
  origin_z:             0.0
  z_resolution:         0.2
  z_voxels:             10
  unknown_threshold:    15
  mark_threshold:       0
  combination_method:   1
  track_unknown_space:  true    #true needed for disabling global path planning through unknown space
  obstacle_range: 2.5
  raytrace_range: 3.0
  origin_z: 0.0
  z_resolution: 0.2
  z_voxels: 10
  publish_voxel_map: false
  observation_sources: scan bump
  scan:
    data_type: LaserScan
    topic: scan
    marking: true
    clearing: true
    min_obstacle_height: 0.25
    max_obstacle_height: 0.35
    inf_is_valid: true
  bump:
    data_type: PointCloud2
    topic: mobile_base/sensors/bumper_pointcloud
    marking: true
    clearing: false
    min_obstacle_height: 0.0
    max_obstacle_height: 0.15
  #camera:
     #data_type: PointCloud2
     #topic: camera/depth/points
     #marking: true
     #clearing: true
     #min_obstacle_height: 0.4
     #max_obstacle_height: 0.8
  # for debugging only, let's you see the entire voxel grid

#cost_scaling_factor and inflation_radius were now moved to the inflation_layer ns
inflation_layer:
  enabled:              true
  cost_scaling_factor:  5.0  # exponential rate at which the obstacle cost drops off (default: 10)
  inflation_radius:     0.5  # max. distance from an obstacle at which costs are incurred for planning paths.

static_layer:
  enabled:              true

2. global_costmap_params.yaml

global_costmap:
   global_frame: /map
   robot_base_frame: /base_footprint
   update_frequency: 1.0 #基于传感器数据更新的频率,降低频率可以减少CPU负载。合理值在1~5
   publish_frequency: 0.5 #对于global static map,通常不需要持续发布
   static_map: true
   transform_tolerance: 0.5 #TF坐标系更新容忍的最大延迟,单位秒
   plugins:
     - {name: static_layer,            type: "costmap_2d::StaticLayer"}
     - {name: obstacle_layer,          type: "costmap_2d::VoxelLayer"}
     - {name: inflation_layer,         type: "costmap_2d::InflationLayer"}

由于在全局路径规划中,我们只应该考虑静态地图,即我们之前slam建立好的地图,所以我们把static_map设为true,rolling_window设为false,再看plugins:有两个层,静态层和膨胀层,这样就完成了global的yaml的配置,如果你需要把障碍物层也添加到全局地图中,plugins加入,同时别忘了在下面声明数据来源。

3. local_costmap_params.yaml

local_costmap:
   global_frame: odom
   robot_base_frame: /base_footprint
   update_frequency: 5.0  基于传感器数据更新的频率,降低频率可以减少CPU负载
   publish_frequency: 2.0  发布地图的更新频率, 1HZ是足够好,除非机器人移动速度更快
   static_map: false
   rolling_window: true
   width: 4.0  rolling局部地图宽
   height: 4.0  rolling局部地图长
   resolution: 0.05   分辨率要与使用地图YAML文件中描述的分辨率一致
   transform_tolerance: 0.5  TF坐标系更新容忍的最大延迟,单位秒
   plugins:
    - {name: obstacle_layer,      type: "costmap_2d::VoxelLayer"}
    - {name: inflation_layer,     type: "costmap_2d::InflationLayer"}

这里由于是局部层,所以我们要把static_map设为fasle,我们并不希望使用静态的地图,因为这不利于我们的局部避障,rollung_window设为true。下面的plugins就为各个层的设置了,在局部路径规划中我们只需要考虑障碍物的信息就可以了,不需要考虑我们之前slam建立的静态地图,所有我们添加了两个图层,即障碍物层和障碍物的膨胀层,下面这个很重要,我们需要声明我们的障碍物层的数据来源,即scan,要把topic对应你的scan的topic,否则你可能发现rviz里的local_costmap没有数据,这就是你没有声明的原因。最后两行为设置膨胀层的半径大小。

4. dwa_local_planner_params.yaml

DWAPlannerROS:

# Robot Configuration Parameters - Kobuki
  max_vel_x: 0.5  # 0.55
  min_vel_x: 0.0 

  max_vel_y: 0.0  # diff drive robot
  min_vel_y: 0.0  # diff drive robot

  max_trans_vel: 0.5 # choose slightly less than the base's capability
  min_trans_vel: 0.1  # this is the min trans velocity when there is negligible rotational velocity
  trans_stopped_vel: 0.1

  # Warning!
  #   do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities
  #   are non-negligible and small in place rotational velocities will be created.

  max_rot_vel: 5.0  # choose slightly less than the base's capability
  min_rot_vel: 0.4  # this is the min angular velocity when there is negligible translational velocity
  rot_stopped_vel: 0.4
  
  acc_lim_x: 1.0 # maximum is theoretically 2.0, but we 
  acc_lim_theta: 2.0
  acc_lim_y: 0.0      # diff drive robot

# Goal Tolerance Parameters
  yaw_goal_tolerance: 0.3  # 0.05
  xy_goal_tolerance: 0.15  # 0.10
  # latch_xy_goal_tolerance: false

# Forward Simulation Parameters
  sim_time: 1.0       # 1.7
  vx_samples: 6       # 3
  vy_samples: 1       # diff drive robot, there is only one sample
  vtheta_samples: 20  # 20

# Trajectory Scoring Parameters
  path_distance_bias: 64.0      # 32.0   - weighting for how much it should stick to the global path plan
  goal_distance_bias: 24.0      # 24.0   - wighting for how much it should attempt to reach its goal
  occdist_scale: 0.5            # 0.01   - weighting for how much the controller should avoid obstacles
  forward_point_distance: 0.325 # 0.325  - how far along to place an additional scoring point
  stop_time_buffer: 0.2         # 0.2    - amount of time a robot must stop in before colliding for a valid traj.
  scaling_speed: 0.25           # 0.25   - absolute velocity at which to start scaling the robot's footprint
  max_scaling_factor: 0.2       # 0.2    - how much to scale the robot's footprint when at speed.

# Oscillation Prevention Parameters
  oscillation_reset_dist: 0.05  # 0.05   - how far to travel before resetting oscillation flags

# Debugging
  publish_traj_pc : true
  publish_cost_grid_pc: true
  global_frame_id: odom


# Differential-drive robot configuration - necessary?
#  holonomic_robot: false

5. move_base_params.yaml

shutdown_costmaps: false

controller_frequency: 5.0
controller_patience: 3.0


planner_frequency: 1.0
planner_patience: 5.0

oscillation_timeout: 10.0
oscillation_distance: 0.2

# local planner - default is trajectory rollout
base_local_planner: "dwa_local_planner/DWAPlannerROS"

base_global_planner: "navfn/NavfnROS" #alternatives: global_planner/GlobalPlanner, carrot_planner/CarrotPlanner

6. global_planner_params.yaml

GlobalPlanner:                                  # Also see: http://wiki.ros.org/global_planner
  old_navfn_behavior: false                     # Exactly mirror behavior of navfn, use defaults for other boolean parameters, default false
  use_quadratic: true                           # Use the quadratic approximation of the potential. Otherwise, use a simpler calculation, default true
  use_dijkstra: true                            # Use dijkstra's algorithm. Otherwise, A*, default true
  use_grid_path: false                          # Create a path that follows the grid boundaries. Otherwise, use a gradient descent method, default false
  
  allow_unknown: true                           # Allow planner to plan through unknown space, default true
                                                #Needs to have track_unknown_space: true in the obstacle / voxel layer (in costmap_commons_param) to work
  planner_window_x: 0.0                         # default 0.0
  planner_window_y: 0.0                         # default 0.0
  default_tolerance: 0.0                        # If goal in obstacle, plan to the closest point in radius default_tolerance, default 0.0
  
  publish_scale: 100                            # Scale by which the published potential gets multiplied, default 100
  planner_costmap_publish_frequency: 0.0        # default 0.0
  
  lethal_cost: 253                              # default 253
  neutral_cost: 50                              # default 50
  cost_factor: 3.0                              # Factor to multiply each cost from costmap by, default 3.0
  publish_potential: true                       # Publish Potential Costmap (this is not like the navfn pointcloud2 potential), default true

7. navfn_global_planner_params.yaml

NavfnROS:
  visualize_potential: false    #Publish potential for rviz as pointcloud2, not really helpful, default false
  allow_unknown: false          #Specifies whether or not to allow navfn to create plans that traverse unknown space, default true
                                #Needs to have track_unknown_space: true in the obstacle / voxel layer (in costmap_commons_param) to work
  planner_window_x: 0.0         #Specifies the x size of an optional window to restrict the planner to, default 0.0
  planner_window_y: 0.0         #Specifies the y size of an optional window to restrict the planner to, default 0.0
  
  default_tolerance: 0.0        #If the goal is in an obstacle, the planer will plan to the nearest point in the radius of default_tolerance, default 0.0
                                #The area is always searched, so could be slow for big values

8. rviz显示

注意:要将rviz的fixed frame设成map,因为map才是global_frame_id。

rviz居然连粒子都可以显示,显示让我对amcl粒子更新有了更深刻的理解。 
首先在参数表里面有几个比较重要的参数。 

~initial_pose_x (double, default: 0.0 meters) 
Initial pose mean (x), used to initialize filter with Gaussian distribution. 
~initial_pose_y (double, default: 0.0 meters) 
Initial pose mean (y), used to initialize filter with Gaussian distribution. 
~initial_pose_a (double, default: 0.0 radians) 
Initial pose mean (yaw), used to initialize filter with Gaussian distribution. 
~initial_cov_xx (double, default: 0.5*0.5 meters) 
Initial pose covariance (x*x), used to initialize filter with Gaussian distribution. 
~initial_cov_yy (double, default: 0.5*0.5 meters) 
Initial pose covariance (y*y), used to initialize filter with Gaussian distribution. 
~initial_cov_aa (double, default: (π/12)*(π/12) radian) 
Initial pose covariance (yaw*yaw), used to initialize filter with Gaussian distribution.

这个代表了你初始化粒子时粒子分布的一个状态,注意要把方差设的大一些,要不所有例子上来就是一坨的就没法玩了。 
参考:http://blog.csdn.net/chenxingwangzi/article/details/50038413

local map在rviz 中Add-> by topic-> local map

2、move_base启动

1.move_base.launch配置。

<launch>
  <include file="$(find turtlebot_navigation)/launch/includes/velocity_smoother.launch.xml"/>
  <include file="$(find turtlebot_navigation)/launch/includes/safety_controller.launch.xml"/>
  
  <arg name="odom_frame_id"   default="odom"/>
  <arg name="base_frame_id"   default="base_footprint"/>
  <arg name="global_frame_id" default="map"/>
  <arg name="odom_topic" default="odom" />
  <arg name="laser_topic" default="scan" />
  <arg name="custom_param_file" default="$(find turtlebot_navigation)/param/dummy.yaml"/>

  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />   
    <rosparam file="$(find turtlebot_navigation)/param/local_costmap_params.yaml" command="load" />   
    <rosparam file="$(find turtlebot_navigation)/param/global_costmap_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/dwa_local_planner_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/move_base_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/global_planner_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/navfn_global_planner_params.yaml" command="load" />
    <!-- external params file that could be loaded into the move_base namespace -->
    <rosparam file="$(arg custom_param_file)" command="load" />
    
    <!-- reset frame_id parameters using user input data -->
    <param name="global_costmap/global_frame" value="$(arg global_frame_id)"/>
    <param name="global_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
    <param name="local_costmap/global_frame" value="$(arg odom_frame_id)"/>
    <param name="local_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
    <param name="DWAPlannerROS/global_frame_id" value="$(arg odom_frame_id)"/>

    <remap from="cmd_vel" to="navigation_velocity_smoother/raw_cmd_vel"/>
    <remap from="odom" to="$(arg odom_topic)"/>
    <remap from="scan" to="$(arg laser_topic)"/>
  </node>
</launch>

2. velocity_smoother.launch配置:

<launch>
  <node pkg="nodelet" type="nodelet" name="navigation_velocity_smoother" args="load yocs_velocity_smoother/VelocitySmootherNodelet mobile_base_nodelet_manager">
    <rosparam file="$(find turtlebot_bringup)/param/defaults/smoother.yaml" command="load"/>
    <remap from="navigation_velocity_smoother/smooth_cmd_vel" to="cmd_vel_mux/input/navi"/>

    <!-- Robot velocity feedbacks; use the default base configuration -->
    <remap from="navigation_velocity_smoother/odometry" to="odom"/>
    <remap from="navigation_velocity_smoother/robot_cmd_vel" to="mobile_base/commands/velocity"/>
  </node>
</launch>

3.safety_controller.launch配置:

<launch>
  <node pkg="nodelet" type="nodelet" name="kobuki_safety_controller" args="load kobuki_safety_controller/SafetyControllerNodelet mobile_base_nodelet_manager">
    <remap from="kobuki_safety_controller/cmd_vel" to="cmd_vel_mux/input/safety_controller"/>
    <remap from="kobuki_safety_controller/events/bumper" to="mobile_base/events/bumper"/>
    <remap from="kobuki_safety_controller/events/cliff" to="mobile_base/events/cliff"/>
    <remap from="kobuki_safety_controller/events/wheel_drop" to="mobile_base/events/wheel_drop"/>
  </node>
</launch>

 

评论 6
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值