ROS机器人Diego制作20-搭载EAI F4激光雷达Hector创建室内地图
ROS机器人Diego制作20-搭载EAI F4激光雷达Hector创建室内地图
说明:
- 介绍如何用F4激光雷达的hector算法创建创建室内地图
- 今天我们就用这款雷达基于ROS的 hector来创建室内地图,先上创建好的室内地图。
步骤:
- 图示:
此图是diego 1#搭载此雷达使用hector创建的。
下载F4的ROS包,执行如下命令:
cd ~/catkin_ws/src
git clone https://github.com/EAIBOT/flashgo.git
cd ..
catkin_make
- 执行完成后在src目录下增加一个flashgo的目录,就是F4的ROS包
- 图示:
修改配置文件中的串口号
F4采用的USB和主板连接,和树莓派连接后,会在系统中出现一个串口,由于Arduino UNO也是通过USB连接串口通信,所以在系统中会出现两个串口设备,在配置中一定区分清楚两个设备对应的串口号
图示:
如上图ttyACM0, 和ttyACM1就是对应的串口号,在diego1#中ttyACM1对应的是arduino,ttyACM0对应的F4激光雷达,我们需要修改对应的参数,首先修改Ardunio的配置文件,在config目录打开my_arduino_params.yaml
图示:
修改arduino_bridge连接的串口为ttyACM1
图示:
修改F4的配置文件,打开flashgo/launch目录下的lidar.launch文件
图示:
修改F4连接的串口为ttyACM0
图示:
编写launch文件
- 创建diego_run_hector_flashgo.launch文件
- 代码如下:
<?xml version="1.0"?>
<launch>
<arg name="tf_map_scanmatch_transform_frame_name" default="/scanmatcher_frame"/>
<arg name="pub_map_odom_transform" value="true"/>
<arg name="map_frame" value="map"/>
<arg name="base_frame" value="base_link"/>
<arg name="odom_frame" value="base_link"/>
<arg name="scan_subscriber_queue_size" default="5"/>
<arg name="scan_topic" default="scan"/>
<arg name="map_size" default="2048"/>
<master auto="start"/>
<include file="$(find flashgo)/launch/lidar.launch" />
<node name="arduino" pkg="ros_arduino_python" type="arduino_node.py" output="screen">
<rosparam file="$(find ros_arduino_python)/config/my_arduino_params.yaml" command="load" />
</node>
<node pkg="tf" type="static_transform_publisher" name="base_frame_2_laser" args="0 0 0 0 0 0 /$(arg base_frame) /laser 100"/>
<node pkg="tf" type="static_transform_publisher" name="map_2_odom" args="0.0 0.0 0.0 0 0 0.0 /odom /$(arg base_frame) 10"/>
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<!-- Frame names -->
<param name="map_frame" value="$(arg map_frame)" />
<param name="base_frame" value="$(arg base_frame)" />
<param name="odom_frame" value="$(arg base_frame)" />
<!-- Tf use -->
<param name="use_tf_scan_transformation" value="true"/>
<param name="use_tf_pose_start_estimate" value="false"/>
<param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>
<!-- Map size / start point -->
<param name="map_resolution" value="0.050"/>
<param name="map_size" value="$(arg map_size)"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5" />
<param name="map_multi_res_levels" value="2" />
<!-- Map update parameters -->
<param name="update_factor_free" value="0.4"/>
<param name="update_factor_occupied" value="0.7" />
<param name="map_update_distance_thresh" value="0.2"/>
<param name="map_update_angle_thresh" value="0.9" />
<param name="laser_z_min_value" value = "-1.0" />
<param name="laser_z_max_value" value = "1.0" />
<!-- Advertising config -->
<param name="advertise_map_service" value="true"/>
<param name="scan_subscriber_queue_size" value="$(arg scan_subscriber_queue_size)"/>
<param name="scan_topic" value="$(arg scan_topic)"/>
<param name="tf_map_scanmatch_transform_frame_name" value="$(arg tf_map_scanmatch_transform_frame_name)" />
</node>
<include file="$(find hector_geotiff)/launch/geotiff_mapper.launch"/>
</launch>
测试
- 现在就可以执行如下代码,来启动激光雷达
roslaunch diego_nav diego_run_hector_flashgo.launch
- 绘制地图
- 这时我们可以通过键盘控制diego#在房间内运动,启动rviz就可以绘制出相应的地图,在不同终端中执行如下命令
rosrun teleop_twist_keyboard teleop_twist_keyboard.py
rosrun rviz rviz
获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号