move_base配置
move_base的使用还是很容易的,安装指令:
sudo apt-get install ros-melodic-navigation
记录下我的配置文件,首先建立一个move_base的launch文件,move_base.launch,内容如下:
<launch>
设置地图的配置文件
<arg name="map" default="mymap.yaml" />
运行地图服务器,并且加载设置的地图-->
<node name="map_server" pkg="map_server" type="map_server" args="$(find base_controller)/maps/$(arg map)"/>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam command="delete" ns="move_base" />
<rosparam file="$(find base_controller)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find base_controller)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find base_controller)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find base_controller)/config/global_costmap_params.yaml" command="load" />
<rosparam file="$(find base_controller)/config/base_local_planner.yaml" command="load" />
<rosparam file="$(find base_controller)/config/move_base_params.yaml" command="load" />
<rosparam file="$(find base_controller)/config/navfn_global_planner_params.yaml" command="load" />
</node>
</launch>
加载了地图服务,然后有6个move_base的配置yaml文件,内容记录如下,costmap_common_params.yaml:
footprint: [[0.3, 0.3], [0.3, -0.3], [-0.3, -0.3], [-0.3, -0.3]] #尺寸
map_type: costmap
obstacle_layer:
enabled: true
max_obstacle_height: 0.6
origin_z: 0.0
z_resolution: 0.2
z_voxels: 5
unknown_threshold: 15
mark_threshold: 0
combination_method: 1
track_unknown_space: true
obstacle_range: 2.5
raytrace_range: 3.0
publish_voxel_map: false
observation_sources: scan
scan:
{
frame_name: laser,
data_type: LaserScan,
topic: /scan,
inf_is_valid: true,
marking: true,
clearing: true,
min_obstacle_height: 0.0,
max_obstacle_height: 0.5}
# for debugging only, let's you see the entire voxel grid
inflation_layer:
enabled: true
cost_scaling_factor: 5.0
inflation_radius: 0.5
static_layer:
enabled: true
local_costmap_params.yaml:
local_costmap:
global_frame: odom
robot_base_frame: base_footprint
update_frequency: 5.0
publish_frequency: 5.0
static_map: false
rolling_window: true
width: 6.0
height: 6.0
resolution: 0.05
transform_tolerance: 1.5
plugins:
- {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
global_costmap_params.yaml:
global_costmap:
global_frame: map
robot_base_frame: base_footprint
update_frequency: 5.0
publish_frequency: 5.0
static_map: true
# rolling_window: false #滚动窗口
resolution: 0.05
transform_tolerance: 1.5
# map_type: costmap
plugins:
- {name: static_layer, type: "costmap_2d::StaticLayer"}
- {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
base_local_planner.yaml:
recovery_behavior_enabled: true
clearing_rotation_allowed: true
TrajectoryPlannerROS:
# Robot Configuration Parameters
max_vel_x: 0.1 #x方向,机器人最大线速度,单位是m/s
min_vel_x: 0.02 #x方向,机器人最小线速度,单位是m/s
max_vel_y: 0.0
min_vel_y: 0.0
max_vel_theta: 0.15 #机器人最大转动速度,单位是rad/s, 0.15--8.6度/s
min_vel_theta: -0.15
min_in_place_vel_theta: 0.1 #机器人最小原地旋转速度,单位rad/s
escape_vel: -0.1 #机器人的逃离速度,即背向相反方向行走速度,单位是m/s
acc_lim_x: 0.1 #在x方向上最大的线加速度,单位是m/s^2
acc_lim_y: 0.0
acc_lim_theta: 0.05 #最大角加速度,单位是rad/s^2
xy_goal_tolerance: 0.2 # 10 cm 表示接近目标允许的误差(m),值不能小于地图的分辨率
yaw_goal_tolerance: 0.2 # about 12 degrees ,接近目标方向(就弧度来说)允许的误差(rad),此值太小会造成机器人在目标附近震荡
latch_xy_goal_tolerance: false
holonomic_robot: false #除非拥有一个全方位的机器人,否则设置为false
sim_time: 2.0 #规划器能看到未来多少秒
sim_granularity: 0.05
angular_sim_granularity: 0.025
vx_samples: 10
vtheta_samples: 20
controller_frequency: 10
meter_scoring: true #gdist_scale和pdist_scale参数是否假设goal_distance和path_distance以米或者单元来表达
pdist_scale: 0.8 #紧贴全局路径比到达目标的相对重要性,如果此值比gdist_scale大,那么机器人会更紧靠全局路径行走
gdist_scale: 0.6 #到达目标比紧靠全局路径的相对重要性,如果此值比pdist_scale大,那么机器人会采取任意路径优先到达目标
occdist_scale: 0.1
heading_lookahead: 0.325
heading_scoring: false
heading_scoring_timestep: 0.8
dwa: true #当模拟轨迹走向未来,是否使用动态窗口法
publish_cost_grid_pc: true
oscillation_reset_dist: 0.4
forward_point_distance: 0.4
move_base_params.yaml:
shutdown_costmaps: false
controller_frequency: 10.0
controller_patience: 15.0 #1.0
planner_frequency: 1.0
planner_patience: 5.0
oscillation_timeout: 10.0
oscillation_distance: 0.2
# default: trajectory rollout
base_local_planner: "dwa_local_planner/DWAPlannerROS"
# navfn/NavfnROS、global_planner/GlobalPlanner、carrot_planner/CarrotPlanner三种;
base_global_planner: "navfn/NavfnROS"
recovery_behavior_enabled: true
recovery_behaviors: [{"name":"super_conservative_reset1", "type":"clear_costmap_recovery/ClearCostmapRecovery"}]
reset_distance: 5.0
navfn_global_planner_params.yaml:
NavfnROS:
visualize_potential: true
allow_unknown: false
planner_window_x: 0.0
planner_window_y: 0.0
default_tolerance: 2.0
将movebase的launch文件加入机器人启动的launch文件中:
<include file="$(find base_controller)/launch/move_base.launch"> 启动move_base
</include>
这样机器启动后,就会启动move_base,订阅的话题可以wiki查看,发布导航点后,move_base将发布一个控制信息的cmd_vel话题,接收该话题,解析后串口发布给底盘控制,以两轮为例,代码如下:
void cmd_vel_callback(const geometry_msgs::Twist& cmd_vel)
{
float linear_temp=0, angular_temp=0;//暂存的线速度和角速度
angular_temp = cmd_vel.angular.z ;//获取/cmd_vel的角速度,rad/s
linear_temp = cmd_vel.linear.x ;//获取/cmd_vel的线速度.m/s
//将转换好的小车速度分量为左右轮速度
left_vel = 60.0 * (linear_temp - 0.5f * angular_temp * wheel_dist) / circumference;
right_vel = 60.0 * (linear_temp + 0.5f * angular_temp * wheel_dist) / circumference;
unsigned short int crc;
unsigned char speed_data[10]={0}; //要发给串口的数据
speed_data[0] = 0xAA;
speed_data[1] = left_vel >> 8; speed_data[2] = left_vel;
speed_data[3] = right_vel >> 8; speed_data[4] = right_vel;
speed_data[5] = 0; //function bit
crc = modbus_CRC(speed_data, 6);
speed_data[6] = crc;
speed_data[7] = crc >> 8;
ser.write(data, 8);
ROS_INFO("left_vel:%d, right_vel:%d", left_vel, right_vel);
}
然后,小车就可以在建立的地图中动起来了。
这里只是粗略记录了整体步骤,细节还有很多需要做起来自己慢慢调试的。