Practice of autonomous navigation car (3)

In the previous blog, we implemented the remote control handle to control the movement of the Pioneer robot, while using the lidar carried by the robot to scan the map. In this blog, we will use the scanned map for navigation and path planning. This mainly involves three modules: map_server package, AMCL package, and move_base package.

2.5 Navigation package configuration

As shown in the figure below, map_server mainly loads the map we scanned before and publishes the costmap map . In the autonomous navigation car, map_server provides two costmaps, one for the global planner in move_base, and the other for The local planner (local_planner) in move_base. Each map has three layers (static layer, dynamic layer, expansion layer). map_server publishes two topics "/map" and "/map_metadata", and "/map" is received by AMCL to match laser sensor data.

AMCL is called “adaptive Monte Carlo positioning”. AMCL receives the current lidar data (/scan), TF transform tree and initial pose estimation (/Initialpose), and matches the positioning robot in the map published by map_server. For location, the AMCL package estimates the TF transformation between the map and the odometer (ie "odom" and "map"), forming an error term, and correcting the "odom" coordinate system. AMCL will publish the positioning data in the TF tree and the topic "/amcl_pose".
Insert picture description here
move_base receives the odometer and the TF tree provided by AMCL, calculates the linear velocity and angular velocity of the robot movement through the internal global planner and local planner, and publishes it to the chassis node through the topic "/cmd_vel" to control the robot.

Here we create a file named "amcl.launch" in the folder "p3at_navigation/launch" to configure the AMCL module:

<launch>
  <arg name="use_map_topic" default="false"/>
  <arg name="scan_topic" default="scan" />

  <node pkg="amcl" type="amcl" name="amcl">
    <param name="use_map_topic" value="$(arg use_map_topic)"/>
    <!-- Publish scans from best pose at a max of 10 Hz -->
    <param name="odom_model_type" value="omni-corrected"/>
    <param name="odom_alpha5" value="0.1"/>
    <param name="gui_publish_rate" value="10.0"/>
    <param name="laser_max_beams" value="720"/>
    <param name="laser_min_range" value="0.1"/>
    <param name="laser_max_range" value="30.0"/>
    <param name="min_particles" value="500"/>
    <param name="max_particles" value="2000"/>
    <!-- Maximum error between the true distribution and the estimated distribution. -->
    <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.2"/>
    <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_model_type" value="likelihood_field"/>
    <!-- Maximum distance to do obstacle inflation on map, for use in likelihood_field model. -->
    <param name="laser_likelihood_max_dist" value="2.0"/>
    <!-- Translational movement required before performing a filter update.  -->
    <param name="update_min_d" value="0.1"/>
    <!--Rotational movement required before performing a filter update. -->
    <param name="update_min_a" value="0.314"/>
    <param name="odom_frame_id" value="odom"/>
    <param name="base_frame_id" value="base_link"/>
    <param name="global_frame_id" value="map"/>
    <!-- Number of filter updates required before resampling. -->
    <param name="resample_interval" value="1"/>
    <!-- Increase tolerance because the computer can get quite busy -->
    <param name="transform_tolerance" value="1.0"/>
    <!-- Exponential decay rate for the slow average weight filter, used in deciding when to recover by adding random poses. A good value might be 0.001. -->
    <param name="recovery_alpha_slow" value="0.0"/>
    <!--Exponential decay rate for the fast average weight filter, used in deciding when to recover by adding random poses. A good value might be 0.1. -->
    <param name="recovery_alpha_fast" value="0.1"/>
    <!-- Initial pose mean -->
    <param name="initial_pose_x" value="0.0" />
    <param name="initial_pose_y" value="0.0" />
    <param name="initial_pose_a" value="0.0" />
    <!-- When set to true, AMCL will subscribe to the map topic rather than making a service call to receive its map.-->
    <param name="receive_map_topic" value="true"/>
    <!--  When set to true, AMCL will only use the first map it subscribes to, rather than updating each time a new one is received. -->
    <param name="first_map_only" value="false"/>
    <remap from="scan" to="$(arg scan_topic)"/>
  </node>

</launch>

Open a new terminal and start map_server

source / catkin_ws/devel/setup.bash
rosrun map_server map_server ~/catkin_ws/src/ pioneer3at_pkg /p3at_navigation /map/cqu_lab.yaml

Then open a new terminal and start the AMCL node

source / catkin_ws/devel/setup.bash
roslaunch p3at_navigation amcl.launch

At this time, we open a new terminal and start RVIZ and add the topic of "/map" to see the map. Since the chassis does not publish the TF with the odom coordinate system, the amcl node will prompt that there is no valid data for map and base_link.
Insert picture description here
Insert picture description here
At this time, we start the node of the chassis again, and click "2D Pose Estimate" in RVIZ to locate normally

source / catkin_ws/devel/setup.bash
roslaunch p3at_bringup p3at_bringup.launch

Insert picture description here
Next, start to configure the move_base module. The move_base module needs five files: local_costmap_params.yaml (local costmap parameter file), global_costmap_params.yaml (global map parameter file), dwa_local_planner_params.yaml (local planner parameter file), global_planner_params. yaml (global planner parameter file), move_base_params.yaml (move_base operating parameters).

Among them, the two files xxx_costmap_params.yaml mainly configure the map, such as the expansion area of ​​the map. The xxx_planner_params.yaml two files are the main planner operating parameters. Basically, these parameters can be configured to run according to the tutorial on the wiki, but they are not very good. Many of the parameters need to be further understood. I mainly refer to these two blogs when configuring: [1] [2] (I will update to the blog after new understanding)

Create a file named "amcl_demo.launch" in the folder "p3at_navigation/launch", and start all nodes in a launch file:

<?xml version="1.0"?>
<launch>
  <arg name="rviz" default="true"/>

  <!-- Map Server -->
 <arg name="map_file" default="$(find p3at_navigation)/map/cqu_lab.yaml"/>
 <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" />

  <!-- AMCL -->
 <include file="$(find p3at_navigation)/launch/include/amcl.launch.xml" />

  <!-- Move Base -->
 <include file="$(find p3at_navigation)/launch/include/move_base.launch.xml" />

  <!-- RViz -->
  <node if="$(arg rviz)" pkg="rviz" type="rviz" name="$(anon rviz)" respawn="false" output="screen" args="-d $(find p3at_navigation)/rviz/localization.rviz" />

</launch>

After configuring move_base, we close all the terminals that were opened before, and open two new terminals. The first terminal starts p3at and the chassis has sensors.

source / catkin_ws/devel/setup.bash
roslaunch p3at_bringup p3at_bringup.launch

Open another terminal to start move_base, map_server and amcl

source / catkin_ws/devel/setup.bash
roslaunch p3at_navigation amcl_demo.launch

Welcome to leave a message to discuss or see the
code of [email protected] on GitHub: https://github.com/RuPingCen/P3AT_Auto_Navigation

Previous: Practice of Autonomous Navigation Car (2)

Guess you like

Origin blog.csdn.net/crp997576280/article/details/99702835
Recommended