工作小笔记——在使用cartographer包的环境中搭建m-explore和rrt-exploration进行自主建图

文章目录

  • 前言
  • 1. 环境要求
  • 2. m-explore包的安装和使用
    • 2.1 安装
    • 2.2 支持cartographer输出的地图格式
      • 2.2.1 新建地图格式转换的node
      • 2.2.2 修改m-explore的订阅地图消息的topic名称
    • 2.3 运行
      • 2.3.1 启动仿真环境
      • 2.3.2 启动cartographer节点
      • 2.3.3 启动map转换节点
      • 2.3.4 启动m-explore
  • 3. rrt-exploration包的安装和使用
    • 3.1 安装
    • 3.2 修改相应topic名称和TF的frame_id
      • 3.2.1 修改simple.launch文件
      • 3.2.2 修改functions.py文件
    • 3.3 增加发布/clicked_point消息的脚本
    • 3.4 运行
      • 3.4.1 启动仿真环境
      • 3.4.2 启动cartographer节点
      • 3.4.3 启动rrt-exploration
      • 3.4.4 发布/clicked_point消息
  • 参考文献


前言

本文记录在之前已经安装完毕cartographer和turtlebot3的完整仿真环境的workspace的基础上安装和使用自主建图包的过程,包括m-explore和rrt-exploration两种包,可以分别独立使用。

1. 环境要求

  • 已经按照https://blog.csdn.net/m0_71775106/article/details/127707299文章的说明安装完成了相应的ros环境配置和cartographer;
  • 已经按照https://blog.csdn.net/m0_71775106/article/details/128303582文章的说明安装了完整的turtlebot3环境(包含move_base的使用。

2. m-explore包的安装和使用

2.1 安装

cd ~/carto_ws/src
git clone -b melodic-devel https://github.com/hrnr/m-explore.git
cd ..
rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y
catkin_make_isolated

2.2 支持cartographer输出的地图格式

m-explore包在计算frontier时使用的地图格式,假定地图中的栅格仅包含三个值:

  • EMPTY
  • UNKNOWN
  • LETHAL OBSTACLE

因此,在 查找时仅会查找在[EMPTY]空间附近的[UNKNOWN]空间作为frontier。而cartographer生成的地图栅格值包含灰度。因此需要进行转换。

2.2.1 新建地图格式转换的node

cd ~/carto_ws/
catkin_create_pkg mypatches
roscd mypatches
mkdir scripts
touch carto_to_gmapping.py

编辑carto_to_gmapping.py文件,增加如下内容:

#!/usr/bin/python
import rospy
from nav_msgs.msg import OccupancyGrid

# ***************
#   OBSTACLE
M = 75
#   unknown
N = 50
#   free
# ----0-----
#   unknown
# ***************
def callback(cmap):
    data = list(cmap.data)
    for y in range(cmap.info.height):
        for x in range(cmap.info.width):
            i = x + (cmap.info.height - 1 - y) * cmap.info.width
            if data[i] >= M:  
                data[i] = 100
            elif (data[i] >= 0) and (data[i] < N):  # free
                data[i] = 0
            else:  # unknown
                data[i] = -1
    cmap.data = tuple(data)
    pub.publish(cmap)

rospy.init_node('mapc_node', anonymous=True)
sub = rospy.Subscriber('/map', OccupancyGrid, callback)
pub = rospy.Publisher('/cmap', OccupancyGrid, queue_size=20)

rospy.spin()

2.2.2 修改m-explore的订阅地图消息的topic名称

修改~/carto_ws/src/m-explore/explore/launch/explore.launch文件,将其中的


修改为


2.3 运行

2.3.1 启动仿真环境

新建一个Terminal窗口,运行如下命令

source ~/carto_ws/devel_isolated/setup.bash
export TURTLEBOT3_MODEL=burger
roslaunch turtlebot3_gazebo turtlebot3_house.launch

2.3.2 启动cartographer节点

新建一个Terminal窗口,运行如下命令

source ~/carto_ws/devel_isolated/setup.bash
export TURTLEBOT3_MODEL=burger
roslaucn turtlebot3_slam turtlebot3_slam.launch slam_methods:=cartographer configuration_basename:=turtlebot3_lds_2d_gazebo.lua

2.3.3 启动map转换节点

新建一个Terminal窗口,运行如下命令

source ~/carto_ws/devel_isolated/setup.bash
rosrun mypatches carto_to_gmapping

2.3.4 启动m-explore

新建一个Terminal窗口,运行如下命令

source ~/carto_ws/devel_isolated/setup.bash
roslaunch explore_lite explore.launch

此时可以从rviz上看到turtlebot3开始自主建图。

3. rrt-exploration包的安装和使用

3.1 安装

cd ~/carto_ws/src
git clone https://github.com/hrnr/rrt-exploration.git
cd ..
rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y
catkin_make_isolated

3.2 修改相应topic名称和TF的frame_id

由于rrt-exploration没有针对melodic版本的分支,需要做相应的手动修改。

3.2.1 修改simple.launch文件

修改~/carto_ws/src/rrt_exploration/launch/simple.launch文件,将


修改为



修改为


在""的节点下,增加一行参数配置:


3.2.2 修改functions.py文件

按下图修改~/carto_ws/src/rrt_exploration/scripts/functions.py文件:
工作小笔记——在使用cartographer包的环境中搭建m-explore和rrt-exploration进行自主建图_第1张图片

3.3 增加发布/clicked_point消息的脚本

rrt_exploration模块需要订阅接收5个/clicked_point消息来确定需要探索的空间区域和起始点,这个动作一般通过rviz上的PublishPoint来完成。为了简化这个过程,可以写一个脚本自动进行此动作:
新建一个文件~/carto_ws/src/mypatches/scripts/pub_clicked_points.sh,增加如下内容:

#!/bin/sh
rostopic pub -1 /clicked_point geometry_msgs/PointStamped "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: 'map'
point:
  x: -5.0
  y: 5.0
  z: 0.0"

rostopic pub -1 /clicked_point geometry_msgs/PointStamped "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: 'map'
point:
  x: -5.0
  y: -5.0
  z: 0.0"
rostopic pub -1 /clicked_point geometry_msgs/PointStamped "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: 'map'
point:
  x: 5.0
  y: -5.0
  z: 0.0"
rostopic pub -1 /clicked_point geometry_msgs/PointStamped "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: 'map'
point:
  x: 5.0
  y: 5.0
  z: 0.0"
rostopic pub -1 /clicked_point geometry_msgs/PointStamped "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: 'map'
point:
  x: 0.0
  y: 0.0
  z: 0.0"

3.4 运行

3.4.1 启动仿真环境

新建一个Terminal窗口,运行如下命令

source ~/carto_ws/devel_isolated/setup.bash
export TURTLEBOT3_MODEL=burger
roslaunch turtlebot3_gazebo turtlebot3_house.launch

3.4.2 启动cartographer节点

新建一个Terminal窗口,运行如下命令

source ~/carto_ws/devel_isolated/setup.bash
export TURTLEBOT3_MODEL=burger
roslaucn turtlebot3_slam turtlebot3_slam.launch slam_methods:=cartographer configuration_basename:=turtlebot3_lds_2d_gazebo.lua

3.4.3 启动rrt-exploration

新建一个Terminal窗口,运行如下命令

source ~/carto_ws/devel_isolated/setup.bash
roslaunch rrt_exploration simple.launch

3.4.4 发布/clicked_point消息

新建一个Terminal窗口,运行如下命令

cd ~/carto_ws/src/mypatches/scripts
source ./pub_clicked_points.sh

此时可以从rviz上看到turtlebot3开始自主建图。

参考文献

  • 工作小笔记——基于ROS Melodic的cartographer安装, https://blog.csdn.net/m0_71775106/article/details/127707299
  • 工作小笔记——安装turtlebot3的ROS gazebo仿真环境并使用cartographer进行建图和定位, https://blog.csdn.net/m0_71775106/article/details/128303582

你可能感兴趣的:(自动驾驶,深度学习,人工智能,机器人,学习)