文章目录
一、概述
二、导航实现
1.导航实现01_准备工作
1)分布式架构
2)功能包安装
3)机器人模型以及坐标变换
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="car_base.urdf.xacro" />
<xacro:include filename="car_camera.urdf.xacro" />
<xacro:include filename="car_laser.urdf.xacro" />
</robot>
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:property name="footprint_radius" value="0.001" />
<link name="base_footprint">
<visual>
<geometry>
<sphere radius="${footprint_radius}" />
</geometry>
</visual>
</link>
<xacro:property name="base_radius" value="0.1" />
<xacro:property name="base_length" value="0.08" />
<xacro:property name="lidi" value="0.015" />
<xacro:property name="base_joint_z" value="${base_length / 2 + lidi}" />
<link name="base_link">
<visual>
<geometry>
<cylinder radius="0.1" length="0.08" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="baselink_color">
<color rgba="1.0 0.5 0.2 0.5" />
</material>
</visual>
</link>
<joint name="link2footprint" type="fixed">
<parent link="base_footprint" />
<child link="base_link" />
<origin xyz="0 0 0.055" rpy="0 0 0" />
</joint>
<xacro:property name="wheel_radius" value="0.0325" />
<xacro:property name="wheel_length" value="0.015" />
<xacro:property name="PI" value="3.1415927" />
<xacro:property name="wheel_joint_z" value="${(base_length / 2 + lidi - wheel_radius) * -1}" />
<xacro:macro name="wheel_func" params="wheel_name flag">
<link name="${wheel_name}_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
</geometry>
<origin xyz="0 0 0" rpy="${PI / 2} 0 0" />
<material name="wheel_color">
<color rgba="0 0 0 0.3" />
</material>
</visual>
</link>
<joint name="${wheel_name}2link" type="continuous">
<parent link="base_link" />
<child link="${wheel_name}_wheel" />
<origin xyz="0 ${0.1 * flag} ${wheel_joint_z}" rpy="0 0 0" />
<axis xyz="0 1 0" />
</joint>
</xacro:macro>
<xacro:wheel_func wheel_name="left" flag="1" />
<xacro:wheel_func wheel_name="right" flag="-1" />
<xacro:property name="small_wheel_radius" value="0.0075" />
<xacro:property name="small_joint_z" value="${(base_length / 2 + lidi - small_wheel_radius) * -1}" />
<xacro:macro name="small_wheel_func" params="small_wheel_name flag">
<link name="${small_wheel_name}_wheel">
<visual>
<geometry>
<sphere radius="${small_wheel_radius}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="wheel_color">
<color rgba="0 0 0 0.3" />
</material>
</visual>
</link>
<joint name="${small_wheel_name}2link" type="continuous">
<parent link="base_link" />
<child link="${small_wheel_name}_wheel" />
<origin xyz="${0.08 * flag} 0 ${small_joint_z}" rpy="0 0 0" />
<axis xyz="0 1 0" />
</joint>
</xacro:macro >
<xacro:small_wheel_func small_wheel_name="front" flag="1"/>
<xacro:small_wheel_func small_wheel_name="back" flag="-1"/>
</robot>
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:property name="camera_length" value="0.02" />
<xacro:property name="camera_width" value="0.05" />
<xacro:property name="camera_height" value="0.05" />
<xacro:property name="joint_camera_x" value="0.08" />
<xacro:property name="joint_camera_y" value="0" />
<xacro:property name="joint_camera_z" value="${base_length / 2 + camera_height / 2}" />
<link name="camera">
<visual>
<geometry>
<box size="${camera_length} ${camera_width} ${camera_height}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="black">
<color rgba="0 0 0 0.8" />
</material>
</visual>
</link>
<joint name="camera2base" type="fixed">
<parent link="base_link" />
<child link="camera" />
<origin xyz="${joint_camera_x} ${joint_camera_y} ${joint_camera_z}" rpy="0 0 0" />
</joint>
</robot>
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:property name="support_radius" value="0.01" />
<xacro:property name="support_length" value="0.15" />
<xacro:property name="laser_radius" value="0.03" />
<xacro:property name="laser_length" value="0.05" />
<xacro:property name="joint_support_x" value="0" />
<xacro:property name="joint_support_y" value="0" />
<xacro:property name="joint_support_z" value="${base_length / 2 + support_length / 2}" />
<xacro:property name="joint_laser_x" value="0" />
<xacro:property name="joint_laser_y" value="0" />
<xacro:property name="joint_laser_z" value="${support_length / 2 + laser_length / 2}" />
<link name="support">
<visual>
<geometry>
<cylinder radius="${support_radius}" length="${support_length}" />
</geometry>
<material name="yellow">
<color rgba="0.8 0.5 0.0 0.5" />
</material>
</visual>
</link>
<joint name="support2base" type="fixed">
<parent link="base_link" />
<child link="support"/>
<origin xyz="${joint_support_x} ${joint_support_y} ${joint_support_z}" rpy="0 0 0" />
</joint>
<link name="laser">
<visual>
<geometry>
<cylinder radius="${laser_radius}" length="${laser_length}" />
</geometry>
<material name="black">
<color rgba="0 0 0 0.5" />
</material>
</visual>
</link>
<joint name="laser2support" type="fixed">
<parent link="support" />
<child link="laser"/>
<origin xyz="${joint_laser_x} ${joint_laser_y} ${joint_laser_z}" rpy="0 0 0" />
</joint>
</robot>
<launch>
<param name="robot_description" command="$(find xacro)/xacro $(find mycar_description)/urdf/car.urdf.xacro" />
<node pkg="joint_state_publisher" name="joint_state_publisher" type="joint_state_publisher" />
<node pkg="robot_state_publisher" name="robot_state_publisher" type="robot_state_publisher" />
</launch>
<launch>
<include file="$(find ros_arduino_python)/launch/arduino.launch" />
<include file="$(find usb_cam)/launch/usb_cam-test.launch" />
<include file="$(find rplidar_ros)/launch/rplidar.launch" />
<!-- 机器人模型加载文件 -->
<include file="$(find mycar_description)/launch/car.launch" />
</launch>
4)结果演示
2.SLAM建图
1)编写gmapping节点相关launch文件
<launch>
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<remap from="scan" to="scan"/>
<param name="base_frame" value="base_footprint"/><!--底盘坐标系-->
<param name="odom_frame" value="odom"/> <!--里程计坐标系-->
<param name="map_update_interval" value="5.0"/>
<param name="maxUrange" value="16.0"/>
<param name="sigma" value="0.05"/>
<param name="kernelSize" value="1"/>
<param name="lstep" value="0.05"/>
<param name="astep" value="0.05"/>
<param name="iterations" value="5"/>
<param name="lsigma" value="0.075"/>
<param name="ogain" value="3.0"/>
<param name="lskip" value="0"/>
<param name="srr" value="0.1"/>
<param name="srt" value="0.2"/>
<param name="str" value="0.1"/>
<param name="stt" value="0.2"/>
<param name="linearUpdate" value="1.0"/>
<param name="angularUpdate" value="0.5"/>
<param name="temporalUpdate" value="3.0"/>
<param name="resampleThreshold" value="0.5"/>
<param name="particles" value="30"/>
<param name="xmin" value="-50.0"/>
<param name="ymin" value="-50.0"/>
<param name="xmax" value="50.0"/>
<param name="ymax" value="50.0"/>
<param name="delta" value="0.05"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
</node>
</launch>
<remap from="scan" to="scan"/><!-- 雷达话题 -->
<param name="base_frame" value="base_footprint"/><!--底盘坐标系-->
<param name="odom_frame" value="odom"/> <!--里程计坐标系-->
2)执行
3.地图服务
1)地图保存launch文件
2)地图读取
<launch>
<arg name="filename" value="$(find nav)/map/nav" />
<node name="map_save" pkg="map_server" type="map_saver" args="-f $(arg filename)" />
</launch>
<launch>
<!-- 设置地图的配置文件 -->
<arg name="map" default="nav.yaml" />
<!-- 运行地图服务器,并且加载设置的地图-->
<node name="map_server" pkg="map_server" type="map_server" args="$(find mycar_nav)/map/$(arg map)"/>
</launch>
4.定位
1)编写amcl节点相关的launch文件
<launch>
<node pkg="amcl" type="amcl" name="amcl" output="screen">
<!-- Publish scans from best pose at a max of 10 Hz -->
<param name="odom_model_type" value="diff"/><!-- 里程计模式为差分 -->
<param name="odom_alpha5" value="0.1"/>
<param name="transform_tolerance" value="0.2" />
<param name="gui_publish_rate" value="10.0"/>
<param name="laser_max_beams" value="30"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="5000"/>
<param name="kld_err" value="0.05"/>
<param name="kld_z" value="0.99"/>
<param name="odom_alpha1" value="0.2"/>
<param name="odom_alpha2" value="0.2"/>
<!-- translation std dev, m -->
<param name="odom_alpha3" value="0.8"/>
<param name="odom_alpha4" value="0.2"/>
<param name="laser_z_hit" value="0.5"/>
<param name="laser_z_short" value="0.05"/>
<param name="laser_z_max" value="0.05"/>
<param name="laser_z_rand" value="0.5"/>
<param name="laser_sigma_hit" value="0.2"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_model_type" value="likelihood_field"/>
<!-- <param name="laser_model_type" value="beam"/> -->
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="update_min_d" value="0.2"/>
<param name="update_min_a" value="0.5"/>
<param name="odom_frame_id" value="odom"/><!-- 里程计坐标系 -->
<param name="base_frame_id" value="base_footprint"/><!-- 添加机器人基坐标系 -->
<param name="global_frame_id" value="map"/><!-- 添加地图坐标系 -->
</node>
</launch>
2)编写测试launch文件
3)执行
<launch>
<!-- 设置地图的配置文件 -->
<arg name="map" default="nav.yaml" />
<!-- 运行地图服务器,并且加载设置的地图-->
<node name="map_server" pkg="map_server" type="map_server" args="$(find nav)/map/$(arg map)"/>
<!-- 启动AMCL节点 -->
<include file="$(find nav)/launch/amcl.launch" />
</launch>
5.路径规划
1)编写launch文件
<launch>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
<rosparam file="$(find nav)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find nav)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find nav)/param/local_costmap_params.yaml" command="load" />
<rosparam file="$(find nav)/param/global_costmap_params.yaml" command="load" />
<rosparam file="$(find nav)/param/base_local_planner_params.yaml" command="load" />
</node>
</launch>
2)编写配置文件
#机器人几何参,如果机器人是圆形,设置 robot_radius,如果是其他形状设置 footprint
robot_radius: 0.12 #圆形
# footprint: [[-0.12, -0.12], [-0.12, 0.12], [0.12, 0.12], [0.12, -0.12]] #其他形状
obstacle_range: 3.0 # 用于障碍物探测,比如: 值为 3.0,意味着检测到距离小于 3 米的障碍物时,就会引入代价地图
raytrace_range: 3.5 # 用于清除障碍物,比如:值为 3.5,意味着清除代价地图中 3.5 米以外的障碍物
#膨胀半径,扩展在碰撞区域以外的代价区域,使得机器人规划路径避开障碍物
inflation_radius: 0.2
#代价比例系数,越大则代价值越小
cost_scaling_factor: 3.0
#地图类型
map_type: costmap
#导航包所需要的传感器
observation_sources: scan
#对传感器的坐标系和数据进行配置。这个也会用于代价地图添加和清除障碍物。例如,你可以用激光雷达传感器用于在代价地图添加障碍物,再添加kinect用于导航和清除障碍物。
scan: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true}
global_costmap:
global_frame: map #地图坐标系
robot_base_frame: base_footprint #机器人坐标系
# 以此实现坐标变换
update_frequency: 1.0 #代价地图更新频率
publish_frequency: 1.0 #代价地图的发布频率
transform_tolerance: 0.5 #等待坐标变换发布信息的超时时间
static_map: true # 是否使用一个地图或者地图服务器来初始化全局代价地图,如果不使用静态地图,这个参数为false.
local_costmap:
global_frame: odom #里程计坐标系
robot_base_frame: base_footprint #机器人坐标系
update_frequency: 10.0 #代价地图更新频率
publish_frequency: 10.0 #代价地图的发布频率
transform_tolerance: 0.5 #等待坐标变换发布信息的超时时间
static_map: false #不需要静态地图,可以提升导航效果
rolling_window: true #是否使用动态窗口,默认为false,在静态的全局地图中,地图不会变化
width: 3 # 局部地图宽度 单位是 m
height: 3 # 局部地图高度 单位是 m
resolution: 0.05 # 局部地图分辨率 单位是 m,一般与静态地图分辨率保持一致
TrajectoryPlannerROS:
# Robot Configuration Parameters
max_vel_x: 0.5 # X 方向最大速度
min_vel_x: 0.1 # X 方向最小速速
max_vel_theta: 1.0 #
min_vel_theta: -1.0
min_in_place_vel_theta: 1.0
acc_lim_x: 1.0 # X 加速限制
acc_lim_y: 0.0 # Y 加速限制
acc_lim_theta: 0.6 # 角速度加速限制
# Goal Tolerance Parameters,目标公差
xy_goal_tolerance: 0.10
yaw_goal_tolerance: 0.05
# Differential-drive robot configuration
# 是否是全向移动机器人
holonomic_robot: false
# Forward Simulation Parameters,前进模拟参数
sim_time: 0.8
vx_samples: 18
vtheta_samples: 20
sim_granularity: 0.05
3)launch文件集成
<launch>
<!-- 设置地图的配置文件 -->
<arg name="map" default="nav.yaml" />
<!-- 运行地图服务器,并且加载设置的地图-->
<node name="map_server" pkg="map_server" type="map_server" args="$(find nav)/map/$(arg map)"/>
<!-- 启动AMCL节点 -->
<include file="$(find nav)/launch/amcl.launch" />
<!-- 运行move_base节点 -->
<include file="$(find nav)/launch/move_base.launch" />
</launch>
4)测试
6.导航与SLAM建图
1)编写launc文件
<launch>
<!-- 启动SLAM节点 -->
<include file="$(find nav)/launch/gmapping.launch" />
<!-- 运行move_base节点 -->
<include file="$(find nav)/launch/move_base.launch" />
</launch>
2)测试
版权声明:本文为Mufafafa原创文章,遵循 CC 4.0 BY-SA 版权协议,转载请附上原文出处链接和本声明。