Introduction
This section will present how to build a map of the environment and use it for the navigation tasks on a real mobile robot. To understand the basics of the mapping and navigation process, you can also help here with the description of AMCL/gmapping, which can be found in the previous tutorial (Day 3, AMCL/gmapping (Gazebo))
SLAM (real robot)
Below is a procedure of building a map of an environment for a real mobile robot. Follow the steps.
Tip: Place (fix) some obstacles (e.g., boxes, walls) near the mobile robot and then do not move them anymore (!obstacles must be high enough for LiDAR to detect them). That is a layout to be used for the mapping process in the following steps.
Step 1. Inside package rosbot_mapping, in the folder .../rosbot_mapping/launch
create a new file and name it mapping.launch
.
Step 2. Open file mapping.launch
and copy the code below in it:
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- COMMUNICATION -->
<node name="rosserial_server" pkg="rosserial_server" type="socket_node" output="screen"/>
<node name="message_info_service" pkg="rosserial_python" type="message_info_service.py" output="screen"/>
<!-- TELEOP -->
<remap from="mouse_vel" to="cmd_vel"/>
<node name="mouse_teleop" pkg="mouse_teleop" type="mouse_teleop.py" output="screen"/>
<!-- TF SETUP -->
<node name="lidartf" pkg="tf" type="static_transform_publisher" args="0.054 0 0.035 0 0 0 1 base_link lidar_link 200" output="screen"/>
<node name="imutf" pkg="tf" type="static_transform_publisher" args="0.080 0 0 0 0 0 1 base_link imu_link 200" output="screen"/>
<node name="lwheeltf" pkg="tf" type="static_transform_publisher" args="0 0.04 0 0 0 0 1 base_link left_wheel_link 200" output="screen"/>
<node name="rwheeltf" pkg="tf" type="static_transform_publisher" args="0 -0.04 0 0 0 0 1 base_link right_wheel_link 200" output="screen"/>
<node name="odom2tf_delayed" pkg="rosbot" type="odom2tf" output="screen">
<param name="odom_frame" value="odom_delayed" />
</node>
<node name="delay" pkg="rosbot" type="delay.py" output="screen"/>
<!-- MAPPING SETUP -->
<node name="gmapping" pkg="gmapping" type="slam_gmapping" output="screen">
<param name="odom_frame" value="odom_delayed"/>
<param name="map_update_interval" value="0.1"/>
<param name="maxUrange" value="1.0"/>
<param name="sigma" value="0.05"/>
<param name="kernelSize" value="2"/>
<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="minimumScore" value="100"/>
<param name="srr" value="0.01"/>
<param name="srt" value="0.02"/>
<param name="str" value="0.01"/>
<param name="stt" value="0.02"/>
<param name="linearUpdate" value="0.01"/>
<param name="angularUpdate" value="0.01"/>
<param name="temporalUpdate" value="-1.0"/>
<param name="resampleThreshold" value="0.5"/>
<param name="particles" value="10"/>
<param name="xmin" value="-1.0"/>
<param name="ymin" value="-1.0"/>
<param name="xmax" value="1.0"/>
<param name="ymax" value="1.0"/>
<param name="delta" value="0.02"/>
<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>
<!-- GUI -->
<node name="rqt_gui" pkg="rqt_gui" type="rqt_gui" output="screen" args = "--perspective-file $(find rosbot)/cfg/rqt_gui.perspective"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find rosbot)/urdf/robot.xacro'"/>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find rosbot)/cfg/mapping.rviz" output="screen"/>
</launch>
Step 3. Run the launch file:
cd .../rosbot_ros/
source devel/setup.bash
roslaunch rosbot_mapping mapping.launch
Step 4. In the RViz, add the needed objects for the mapping process (mobile robot position, laser scan, map).
Step 5. Using the mouse_teleop gui, drive the mobile robot around in such a way that the entire map for the environment in which the mobile robot operates is built. The current status of the map can be monitored in RViz.
Step 6. Save the built map:
rosrun map_server map_saver -f my_map1
The map will be saved in a workspace folder .../rosbot_ros
.
Using a newly created map for navigation tasks
Step 1. The my_map1.pgm
and my_map1.yaml
files created with the mapping process must be copied to the folder …/rosbot/map/
.
Step 2. In package rosbot inside .../rosbot/launch
folder create a new file and name it rosbot_with_navigation.launch
.
Step 3. Open rosbot_with_navigation.launch
file and paste in it the code below:
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- COMMUNICATION -->
<node name="rosserial_server" pkg="rosserial_server" type="socket_node" output="screen"/>
<node name="message_info_service" pkg="rosserial_python" type="message_info_service.py" output="screen"/>
<!-- TELEOP -->
<remap from="mouse_vel" to="cmd_vel"/>
<node name="mouse_teleop" pkg="mouse_teleop" type="mouse_teleop.py" output="screen"/>
<!-- TF SETUP -->
<node name="lidartf" pkg="tf" type="static_transform_publisher" args="0.054 0 0.035 0 0 0 1 base_link lidar_link 200" output="screen"/>
<node name="imutf" pkg="tf" type="static_transform_publisher" args="0.080 0 0 0 0 0 1 base_link imu_link 200" output="screen"/>
<node name="lwheeltf" pkg="tf" type="static_transform_publisher" args="0 0.04 0 0 0 0 1 base_link left_wheel_link 200" output="screen"/>
<node name="rwheeltf" pkg="tf" type="static_transform_publisher" args="0 -0.04 0 0 0 0 1 base_link right_wheel_link 200" output="screen"/>
<node name="odom2tf_delayed" pkg="rosbot" type="odom2tf" output="screen">
<param name="odom_frame" value="odom_delayed" />
</node>
<node name="delay" pkg="rosbot" type="delay.py" output="screen"/>
<!-- navigation, map server -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find rosbot)/cfg/costmap_common_params.yaml" command="load" ns="global_costmap"/>
<param name="global_costmap/scan/sensor_frame" type="str" value="lidar_link"/>
<param name="global_costmap/scan/topic" type="str" value="scan"/>
<rosparam file="$(find rosbot)/cfg/costmap_common_params.yaml" command="load" ns="local_costmap"/>
<param name="local_costmap/scan/sensor_frame" type="str" value="lidar_link"/>
<param name="local_costmap/scan/topic" type="str" value="scan"/>
<rosparam file="$(find rosbot)/cfg/local_costmap_params.yaml" command="load"/>
<param name="local_costmap/global_frame" type="str" value="odom"/>
<param name="local_costmap/robot_base_frame" type="str" value="base_link"/>
<rosparam file="$(find rosbot)/cfg/global_costmap_params.yaml" command="load"/>
<param name="global_costmap/global_frame" type="str" value="map" />
<param name="global_costmap/robot_base_frame" type="str" value="base_link"/>
<rosparam file="$(find rosbot)/cfg/base_local_planner_params.yaml" command="load"/>
<rosparam file="$(find rosbot)/cfg/move_base_params.yaml" command="load"/>
</node>
<node name="map_server" pkg="map_server" type="map_server" args="$(find rosbot)/map/my_map1.yaml" output="screen" respawn="true">
<param name="frame_id" value="map"/>
</node>
<!-- GUI -->
<node name="rqt_gui" pkg="rqt_gui" type="rqt_gui" output="screen" args = "--perspective-file $(find rosbot)/cfg/rqt_gui.perspective"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find rosbot)/urdf/robot.xacro'"/>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find rosbot)/cfg/mapping.rviz" output="screen"/>
<!-- Align map and odom frames -->
<!-- <node pkg="tf" type="static_transform_publisher" name="odom_publisher_odom__odom_delayed" args="0 0 0 0 0 0 1 odom odom_delayed 100" /> -->
<node pkg="tf" type="static_transform_publisher" name="odom_publisher_map_odom" args="0 0 0 0 0 0 1 map odom 100" />
<remap from="/amcl_pose" to="/tb_current_pose"/>
<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-corrected"/>
<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="200"/>
<param name="max_particles" value="2000"/>
<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="odom_frame_id" value="odom_delayed"/>
<param name="base_frame_id" value="base_link"/>
<param name="global_frame_id" value="map"/>
<param name="tf_broadcast" value="true"/>
<!-- <param name="laser_likelihood_max_dist" value="2.0"/>
<param name="update_min_d" value="0.002"/>
<param name="update_min_a" value="0.005"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.1"/>
<param name="recovery_alpha_slow" value="0.002"/>
<param name="recovery_alpha_fast" value="0.1"/>
<param name="odom_alpha1" value="0.4"/>
<param name="odom_alpha2" value="0.4"/>
<param name="odom_alpha3" value="0.4"/>
<param name="odom_alpha4" value="0.4"/> -->
</node>
</launch>
Step 4. Run the launch file:
cd .../rosbot_ros/
source devel/setup.bash
roslaunch rosbot rosbot_with_navigation.launch
Step 5. Tune the move_base, amcl, etc. parameters (most likely, the microcontroller program also needs to be modified).
Step 6. Try moving the mobile robot around by sending new goal positions and orientations to move_base node via RViZ GUI (click on a green arrow on the upper side of the GUI window, and then click to a target location on a map). The mobile robot should drive to the target location and avoid obstacles when driving.
Additional task: Add an obstacle to the layout (e.g. add another wall) and test whether the mobile robot can detect and avoid this obstacle, even though this obstacle is not included in the map of the environment.