Getting Started with Jetson Nano's ROS - - SLAM's Gmapping Mapping and Path Planning


foreword

insert image description here

SLAM (Simultaneous Localization And Mapping) refers to a technology that simultaneously constructs an environmental map and determines its own position in real time during the movement of an autonomous mobile system such as a robot or a mobile device. SLAM technology has been widely used in unmanned driving, robot navigation, virtual reality and other fields.

In SLAM technology, the robot needs to obtain environmental information through its own sensors, such as lidar, camera, inertial measurement unit, etc., and then realize autonomous movement and position estimation through algorithms, and at the same time convert the environmental information into a map. SLAM technology can be divided into two main parts, front-end and back-end.

The front end is responsible for extracting feature points or landmarks from sensor data, and tracking and matching these information through various algorithms, so as to realize real-time positioning and mapping of robots. Commonly used front-end algorithms include lidar-based algorithms, vision-based algorithms, and inertial measurement unit-based algorithms.

The back-end is responsible for processing and optimizing the data obtained by the front-end, merging the position information obtained from multiple measurements, generating a more accurate map, and correcting and optimizing the trajectory of the robot. Commonly used back-end algorithms include graph optimization-based algorithms and filtering-based algorithms.

Commonly used lidar-based SLAM algorithms include the classic Gmapping algorithm and Hector SLAM algorithm; commonly used vision-based SLAM algorithms include ORB-SLAM, LSD-SLAM, DSO, etc.


1. Gmapping algorithm

The GMapping algorithm is a classic laser SLAM algorithm that is widely used in mobile robot construction. It uses particle filters to estimate the position of the mobile robot in the environment and simultaneously builds a map of the environment.
insert image description here

1. Gmapping algorithm process principle

The SLAM problem can be described as a series of sensor measurement data z 1 : t z1:t of the mobile robot from power-on to time twith 1:t (of course /scan here) and a series of control datau 1 : t u1:tat 1:Under the condition of t (here considered to be /odom), at the same time, the mapmmm , robot posex 1 : t x1:tx 1:The estimate made by t is obviously a conditional joint probability distribution

insert image description here

A particle filter is a probabilistic filter based on the Monte Carlo method for estimating time-varying state quantities. It represents the uncertainty of the current state by randomly sampling a set of particles in the state space, and calculates the posterior probability distribution of the state by weighting these particles. In robot localization and mapping problems, particle filters are often used to estimate the pose of the robot in the environment and the characteristics of the map.

insert image description here

ut u_tutIndicates that the robot at time ttt tot+1 t+1t+Motion model between 1 , zt z_tztIndicates that the robot at time ttThe sensor measurement result of t . The particle filter passes a set of particlesst [ 1 : M ] s_t^{[1:M]}st[1:M]to represent the robot at time ttUncertainties in the location of t and map features, where MMM represents the number of particles, each particle contains a pose vectorxt [ m ] x_t^{[m]}xt[m]and map feature vector mt [ m ] m_{t}^{[m]}mt[m]

In the prediction step, for each particle xt [ m ] x_t^{[m]}xt[m], to make predictions based on the robot's motion model:

x ˉ t + 1 [ m ] = u t ( x t [ m ] ) + ϵ t [ m ] \bar{x}_{t+1}^{[m]} = u_t(x_t^{[m]}) + \epsilon_t^{[m]} xˉt+1[m]=ut(xt[m])+ϵt[m]

where x ˉ t + 1 [ m ] \bar{x}_{t+1}^{[m]}xˉt+1[m]Represents the predicted pose state at the next moment, ut ( xt [ m ] ) u_t(x_t^{[m]})ut(xt[m]) represents the predicted state of the robot according to the motion model,ϵ t [ m ] \epsilon_t^{[m]}ϵt[m]represents the prediction error. It is assumed here that the prediction error obeys a zero-mean Gaussian distribution, that is, ϵ t [ m ] ∼ N ( 0 , Σ t ) \epsilon_t^{[m]} \sim \mathcal{N}(0, \Sigma_t)ϵt[m]N(0,St) , whereΣ t \Sigma_tStis the covariance matrix of the forecast errors. In the measurement update step, for each particle's pose xt + 1 [ m ] x_{t+1}^{[m]}xt+1[m], calculate its weight wt + 1 [ m ] w_{t+1}^{[m]}wt+1[m], which represents the posterior probability distribution of the current particle:

w t + 1 [ m ] = P ( z t + 1 ∣ x t + 1 [ m ] , m t [ m ] ) ⋅ P ( x t + 1 [ m ] ∣ x t [ m ] , u t ) w_{t+1}^{[m]} = P(z_{t+1}|x_{t+1}^{[m]}, m_{t}^{[m]}) \cdot P(x_{t+1}^{[m]}|x_t^{[m]}, u_t) wt+1[m]=P(zt+1xt+1[m],mt[m])P(xt+1[m]xt[m],ut)

其中 P ( z t + 1 ∣ x t + 1 [ m ] , m t [ m ] ) P(z_{t+1}|x_{t+1}^{[m]},m_{t}^{[m]}) P(zt+1xt+1[m],mt[m]) indicates the matching degree of sensor measurement results and map features,mt [ m ] m_{t}^{[m]}mt[m]Represents the characteristics of the current map. P ( xt + 1 [ m ] ∣ xt [ m ] , ut ) P(x_{t+1}^{[m]}|x_t^{[m]}, u_t)P(xt+1[m]xt[m],ut) means that the robot at timettt tot+1 t+1t+The probability density function of the motion model between 1 .

In the resampling step, particles are resampled according to their weights. Specifically, for each particle st [ m ] s_t^{[m]}st[m], according to its weight wt [ m ] w_t^{[m]}wt[m]Sample it to get a new set of particles st + 1 [ 1 : M ] s_{t+1}^{[1:M]}st+1[1:M], making particles with larger weights have a higher probability of being sampled.

Finally, by weighting the average of all particles, the robot can be obtained at time t + 1 t+1t+Estimates of location and map features for 1 :

s ^ t + 1 = ∑ m = 1 M w t + 1 [ m ] s t + 1 [ m ] \hat{s}_{t+1} = \sum_{m=1}^M w_{t+1}^{[m]} s_{t+1}^{[m]} s^t+1=m=1Mwt+1[m]st+1[m]

By continuously iterating the above steps, the particle filter can gradually converge to the correct robot pose and map features.

2. Gmapping map construction practice

First open the terminal, install the Gmapping function package corresponding to the ROS version, a keyboard control package, and a map service package

sudo apt-get install ros-melodic-gmapping
sudo apt-get install ros-melodic-teleop_twist_keyboard
sudo apt install ros-melodic-map-server

The core node in the gmapping function package is: slam_gmapping. Details of the topics subscribed to, published topics, services and related parameters of this node are as follows:

2.1 Subscribed Topic
tf (tf/tfMessage): used for coordinate transformation messages between radar, chassis and odometer.
scan(sensor_msgs/LaserScan): Radar information required by SLAM.

Topic map_metadata (nav_msgs/MapMetaData) released in 2.2
: Map metadata, including map width, height, resolution, etc., this message will be updated regularly.
map(nav_msgs/OccupancyGrid): map raster data, generally displayed graphically in rviz.
~entropy(std_msgs/Float64): Estimation of robot pose distribution entropy (the larger the value, the greater the uncertainty).

2.3 service
dynamic_map (nav_msgs/GetMap): used to obtain map data.

2.4 Parameters
~base_frame(string, default: "base_link"): the base coordinate system of the robot.
~map_frame (string, default: "map"): map coordinate system.
~odom_frame (string, default: "odom"): odometry frame.
~map_update_interval(float, default: 5.0): map update frequency, the update interval is designed according to the specified value.
~maxUrange (float, default: 80.0): Maximum usable range for laser detection (beyond this threshold, truncated).
~maxRange(float): The maximum range of laser detection.

Create a new launch folder and launch file in the workspace, and copy the following launch file parameter configuration

<launch>
<param name="use_sim_time" value="true"/> <!--使用仿真时间-->
    <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>

    <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" />

    <node pkg="rviz" type="rviz" name="rviz" />
</launch>

Then start the Gazebo simulation environment and load the robot model, then use the roslaunch command to execute the launch file

roslaunch 包名 launch文件名

Load RobotModel, Map, LaserScan and other plug-ins in the rviz configuration bar, and start the keyboard control node in the terminal

rosrun teleop_twist_keyboard teleop_twist_keyboard

Then use the keyboard to control the movement of the robot and build the map in real time, and the obtained grid map can be saved through the map_server nodeinsert image description here

Run the rosrun command on the terminal to run the map_server node to save the grid map to the specified path

rosrun map_server map_saver map:=/<Map Topic> -f PATH_TO_YOUR_FILE/mymap

2. AMCL Monte Carlo positioning

1. Principle of adaptive Monte Carlo positioning algorithm

insert image description here

AMCL (Adaptive Monte Carlo Localization) is a particle filter based robot localization method whose main goal is to estimate the robot's pose in the environment based on sensor data.

Our goal is to estimate the pose of the robot at time t, using xt x_txtExpress, use ut u_tutIndicates the motion model from time t-1 to t, zt z_tztIndicates the observation data at time t. According to Bayesian theorem, it can be expressed that the robot pose is estimated under the conditions of motion model and observation data as:

p ( x t ∣ z 1 : t , u 1 : t ) = p ( z t ∣ x t , z 1 : t − 1 , u 1 : t ) ⋅ p ( x t ∣ z 1 : t − 1 , u 1 : t ) p ( z t ∣ z 1 : t − 1 , u 1 : t ) p(x_t | z_{1:t}, u_{1:t}) = \frac{p(z_t | x_t, z_{1:t-1}, u_{1:t}) \cdot p(x_t | z_{1:t-1}, u_{1:t})}{p(z_t | z_{1:t-1}, u_{1:t})} p(xtz1:t,u1:t)=p(ztz1:t1,u1:t)p(ztxt,z1:t1,u1:t)p(xtz1:t1,u1:t)

To calculate p ( xt ∣ z 1 : t − 1 , u 1 : t ) p(x_t | z_{1:t-1}, u_{1:t})p(xtz1:t1,u1:t) , we need to introduce a conditional probabilityp ( xt ∣ xt − 1 , ut ) p(x_t | x_{t-1}, u_t)p(xtxt1,ut) said. It describes the pose xt − 1 x_{t-1}at a given last momentxt1and the current motion model ut u_tutNext, the current pose of the robot xt x_txtprobability distribution. Applying the total probability formula, the motion model can be expressed according to the specific motion characteristics of the robot

p ( x t ∣ z 1 : t − 1 , u 1 : t ) = ∫ p ( x t ∣ x t − 1 , u t ) ⋅ p ( x t − 1 ∣ z 1 : t − 1 , u 1 : t − 1 ) d x t − 1 p(x_t | z_{1:t-1}, u_{1:t}) = \int p(x_t | x_{t-1}, u_t) \cdot p(x_{t-1} | z_{1:t-1}, u_{1:t-1}) dx_{t-1} p(xtz1:t1,u1:t)=p(xtxt1,ut)p(xt1z1:t1,u1:t1)dxt1

为了计算 p ( z t ∣ x t , z 1 : t − 1 , u 1 : t ) p(z_t | x_t, z_{1:t-1}, u_{1:t}) p(ztxt,z1:t1,u1:t) , we need to introduce an observation model, usep ( zt ∣ xt ) p(z_t | x_t)p(ztxt) said. This model describes that at a given current positionxt x_txtNext, the observed data zt z_tztprobability distribution.

The Monte Carlo positioning method uses a particle filter (Particle Filter) to approximate and calculate the above probability distribution. We use a set of particles X t = xt ( 1 ) , xt ( 2 ) , ⋯ , xt ( M ) X_t = {x_t^{(1)}, x_t^{(2)}, \cdots, x_t^{( M)}}Xt=xt(1),xt(2),,xt(M)to represent the pose distribution at time t, MMM is the number of particles.

According to the motion model, from the particle set X t − 1 at time t-1 X_{t-1}Xt1and motion model ut u_tutPredict the particle set X t at time t X_tXt, for each particle xt − 1 ( i ) x_{t-1}^{(i)}xt1(i), we can according to the motion model p ( xt ∣ xt − 1 ( i ) , ut ) p(x_t | x_{t-1}^{(i)}, u_t)p(xtxt1(i),ut) sampling to obtain a new particlext ( i ) x_t^{(i)}xt(i).
According to the observation model, calculate each new particle xt ( i ) x_t^{(i)}xt(i)Weight wt ( i ) w_t^{(i)}wt(i), for each particle xt ( i ) x_t^{(i)}xt(i), we can calculate the observed data zt z_tztThe likelihood p ( zt ∣ xt ( i ) ) p(z_t | x_t^{(i)})p(ztxt(i)) , and then use it as the weight of the particle. According to the weight of the new particlewt ( i ) w_t^{(i)}wt(i)Perform resampling to generate a new particle set X t X_tXt. During this process, particles with larger weights have a higher probability of being sampled multiple times, while particles with smaller weights may be discarded. This process helps to concentrate particle collections in high-probability areas, thereby improving localization accuracy.

A key feature of AMCL is to adaptively adjust the resampling frequency, which is adaptively adjusted according to the effective sample size (ESS) of the particle weight. The ESS is calculated as follows:

N e f f = 1 ∑ i = 1 M w t ( i ) 2 N_{eff} = \frac{1}{\sum_{i=1}^{M} {w_t^{(i)}}^2} Neff=i=1Mwt(i)21

N e f f N_{eff} NeffBelow a threshold (eg half of the total particle count), a resampling step is performed. This prevents particle set degradation caused by premature resampling and reduces computational overhead. The AMCL Monte Carlo localization method estimates the robot position through a particle filter and an adaptive resampling strategy. This method shows good robustness and real-time performance in the robot localization problem.

2. AMCL positioning practice

First open the terminal and install the navigation function package corresponding to the ROS version, which includes the amcl positioning function

sudo apt-get install ros-melodic-navigation

The core node in the amcl function package is: amcl. The topics subscribed to, published topics, services and related parameters of this node are detailed as follows:

3.1 Subscribed Topic
scan (sensor_msgs/LaserScan): lidar data.
tf(tf/tfMessage): Coordinate transformation message.
initialpose(geometry_msgs/PoseWithCovarianceStamped): Used to initialize the mean and covariance of the particle filter.
map(nav_msgs/OccupancyGrid): Get map data.

Topic amcl_pose(geometry_msgs/PoseWithCovarianceStamped) released in 3.2
: The pose estimation of the robot in the map.
particlecloud(geometry_msgs/PoseArray): Pose estimation collection, which can be subscribed by PoseArray in rviz and then graphically display the pose estimation collection of the robot.
tf(tf/tfMessage): publishes the conversion from odom to map.

3.3 Service
global_localization (std_srvs/Empty): Initialize the global positioning service.
request_nomotion_update(std_srvs/Empty): A service that manually performs updates and publishes updated particles.
set_map(nav_msgs/SetMap): Service to manually set new map and pose.
static_map(nav_msgs/GetMap): Call this service to get map data.

3.5 Parameters
~odom_model_type(string, default: "diff"): odometer model selection: "diff", "omni", "diff-corrected", "omni-corrected" (diff differential, omni omnidirectional wheel) ~
odom_frame_id (string, default: "odom"): The odometry coordinate system.
~base_frame_id (string, default: "base_link"): robot polar coordinate system.
~global_frame_id (string, default: "map"): map coordinate system.

Create a new launch file under the launch folder in the workspace, and copy the following launch file parameter configuration

<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"/><!-- 添加地图坐标系 -->

  <param name="resample_interval" value="1"/>
  <param name="transform_tolerance" value="0.1"/>
  <param name="recovery_alpha_slow" value="0.0"/>
  <param name="recovery_alpha_fast" value="0.0"/>
</node>
</launch>

Create a new launch file as a running script, and include the launch configuration file of amcl above

<launch>
    <!-- 设置地图的配置文件 -->
    <arg name="map" default="nav.yaml" />
    <!-- 运行地图服务器,并且加载设置的地图-->
    <node name="map_server" pkg="map_server" type="map_server" args="$(find mycar_nav)/map/$(arg map)"/>
    <!-- include一下上面amcl的launch配置文件,启动AMCL节点 -->
    <include file="$(find mycar_nav)/launch/amcl.launch" />
    <!-- 运行rviz -->
    <node pkg="rviz" type="rviz" name="rviz"/>
</launch>

Then start the Gazebo simulation environment and load the robot model, then use the roslaunch command to execute the launch file

roslaunch 包名 launch文件名

Load RobotModel, Map, PoseArray and other plug-ins in the rviz configuration bar, and start the keyboard control node in the terminal

rosrun teleop_twist_keyboard teleop_twist_keyboard

Then use the keyboard to control the movement of the robot, and observe that the red arrows around the robot represent the real-time positioning estimation of the robot. The denser the arrows, the higher the probability of the robot appearing.
insert image description here

3. move_base path planning

move_base is a package of functions for moving the chassis, providing a way for the robot to safely navigate to the target position in the map. move_base combines the global path planner and the local path planner to form a complete navigation framework.

1. Introduction to path planning algorithm

move_base uses a variety of path planning and navigation algorithms, including global path planning and local path planning. The global path planning is mainly used to find the optimal path from the robot's current position to the target position in the known map, and the local path planning is mainly used to adjust the robot's motion in real time according to the globally planned path, so that it can avoid the unknown path in the map. obstacle.

insert image description here

Commonly used global path planning algorithms are

A algorithm : A* is a heuristic search algorithm that combines optimality (Dijkstra's algorithm) and heuristic information (Greedy Best-First-Search algorithm) to find the shortest path. The key idea of ​​the A* algorithm is to estimate the minimum cost from the starting point to the target point at each step, and select the node with the minimum estimated cost in the search tree to expand.

Dijkstra's Algorithm : Dijkstra's Algorithm is also a search algorithm used to find the shortest paths from a source node to all other nodes in the graph. It selects the node with the smallest distance value among the currently unprocessed nodes in each step, and updates the distance value according to the neighbor nodes of this node.

RRT (Rapidly-exploring Random Trees) algorithm : RRT is an incremental path planning algorithm based on random sampling. It rapidly expands in the search space in the form of a tree until it finds a path from the starting point to the goal point. The RRT algorithm is suitable for dealing with high-dimensional and complex environments.

The local path planning algorithm has

DWA (Dynamic Window Approach) : DWA is a local path planning algorithm based on velocity space search. It searches a set of feasible velocities in the robot's velocity space, and then selects the optimal velocity to control the robot's motion according to the global path and local obstacles.

TEB (Timed Elastic Band) : TEB is an optimization-based local path planning algorithm. It represents the global path as a sequence of time-dependent configurations (positions and velocities), and treats it as an elastic band. By optimizing the shape of the elastic band, local obstacles can be avoided while satisfying dynamic constraints.

2. Introduction to the price map

Costmap (Costmap) is a map type commonly used in ROS for robot path planning and obstacle avoidance, which represents the travel cost of the robot in different positions and directions. A cost map is usually expressed based on a grid. Each grid represents a small area on the map, and its value represents the cost of traveling in this area.

insert image description here
The cost map in move_base can be constructed in the following ways

staticLayer Static map layer : Static maps are maps collected by sensors such as lidar or depth cameras before the robot runs, and can be published through the map_server software package in ROS. move_base can directly subscribe to the static map message and convert it into a cost map. The static map layer simply converts the pixel value in the grayscale image into the cost value in the ros cost map

ObstacleLayer obstacle map layer : before the robot starts to move, move_base will add an obstacle map layer. This layer is composed of obstacles around the robot, such as people, vehicles, furniture, etc. This layer will move with the robot according to the lidar, etc. Sensors are updated in real time to ensure robots can avoid collisions

inflationLayer expansion layer : move_base will add an expansion layer on the basis of the obstacle map layer. This layer can expand the obstacles around the robot to a safe distance, so that the cost map can more clearly show the available space of the robot and avoid the shell of the robot. Or protruding and hitting an obstacle by mistake

The cost calculation method based on the cost map in move_base

From the cost curve above, we can know that the horizontal axis is the distance from the center of the robot, and the vertical axis is the gray value of the grid in the cost map. When configuring parameters, you need to specify the cost value calculation formula for each grid in the cost map , and the weights of obstacles, slopes, and other factors to ensure the accuracy and adaptability of the costmap

(1) Fatal obstacle: grid value is 254;
(2) Inscribed obstacle: grid value is 253;
(3) Circumscribed obstacle: grid value is [128,252];
(4) Non-free space: grid value is (0,127];
(5) Free area: grid value is 0;
(6) Unknown area: grid value is 255;

2. Move_base path planning practice

The core node in the move_base function package is: move_base. The details of the action, subscribed topic, published topic, service and related parameters of this node are as follows:

2.1 Action
move_base/goal (move_base_msgs/MoveBaseActionGoal): the motion planning goal of move_base.
move_base/cancel(actionlib_msgs/GoalID): Cancel the goal.
move_base/feedback(move_base_msgs/MoveBaseActionFeedback): continuous feedback information, including robot chassis coordinates.
move_base/status (actionlib_msgs/GoalStatusArray): Goal status information sent to move_base.
move_base/result(move_base_msgs/MoveBaseActionResult)

2.2 Subscribed Topic
move_base_simple/goal(geometry_msgs/PoseStamped): motion planning goal (compared with action, there is no continuous feedback, and the execution status of the robot cannot be tracked).


Topic cmd_vel(geometry_msgs/Twist) released in 2.3 : Motion control messages output to the robot chassis.

2.4 Service
~make_plan(nav_msgs/GetPlan): Request this service to get the planned path of a given target, but the path planning is not executed.
~clear_unknown_space(std_srvs/Empty): Allows the user to directly clear unknown spaces around the robot.
~clear_costmaps(std_srvs/Empty): Allows clearing obstacles in the cost map, which may cause the robot to collide with obstacles, please use with caution.

Create a new param directory under the function package, and create cost map configuration files such as costmap_common_params.yaml, local_costmap_params.yaml, global_costmap_params.yaml, and base_local_planner_params.yaml under the param directory

costmap_common_params.yaml

#机器人几何参数,如果机器人是圆形,设置 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_params.yaml

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_params.yaml

local_costmap:
  global_frame: map #地图坐标系
  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,一般与静态地图分辨率保持一致

base_local_planner_params

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

Then write the launch file and configure the move_base node, amcl positioning node and map service node

<launch>
    <!-- 设置地图的配置文件 -->
    <arg name="map" default="nav.yaml" />
    <!-- 运行地图服务器,并且加载设置的地图-->
    <node name="map_server" pkg="map_server" type="map_server" args="$(find mycar_nav)/map/$(arg map)"/>
    <!-- 启动AMCL节点 -->
    <include file="$(find mycar_nav)/launch/amcl.launch" />

    <!-- 运行move_base节点 -->
    <include file="$(find mycar_nav)/launch/path.launch" />
    <!-- 运行rviz -->
    <node pkg="rviz" type="rviz" name="rviz" />

</launch>

Then start the Gazebo simulation environment and load the robot model, then use the roslaunch command to execute the launch file

roslaunch 包名 launch文件名

Load RobotModel, Map, Odometry, Path and other plug-ins in the rviz configuration bar, and set the destination in the 2D Nav Goal of the toolbar to realize path planning

insert image description here


Summarize

The above is the entire content of the Gmapping mapping and path planning study notes of SLAM. The Gmapping algorithm can construct a high-precision environmental map through real-time analysis and processing of robot sensor data, and can realize real-time update of the environmental map, providing an important basis for path planning. Apply the path planning algorithm to help the robot find the shortest path in the environment, and can update the path planning results in real time to adapt to environmental changes.

Guess you like

Origin blog.csdn.net/m0_55202222/article/details/131065091