0开始配置Cartographer建图和导航定位

0开始配置Cartographer

日期:12-19

硬件:激光雷达+IMU

小车的tf变换:

建图配置

lua文件配置:my_robot.lua

lua 复制代码
include "map_builder.lua"
include "trajectory_builder.lua"

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "imu_link",
  published_frame = "base_link",
  odom_frame = "odom",
  provide_odom_frame = true,
  publish_frame_projected_to_2d = true,
  use_pose_extrapolator = false,
  use_odometry = false,
  use_nav_sat = false,
  use_landmarks = false,
  num_laser_scans = 1,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 10,
  num_point_clouds = 0,
  lookup_transform_timeout_sec = 0.2,
  submap_publish_period_sec = 0.3,
  pose_publish_period_sec = 5e-3,
  trajectory_publish_period_sec = 30e-3,
  rangefinder_sampling_ratio = 1.,
  odometry_sampling_ratio = 1.,
  fixed_frame_pose_sampling_ratio = 1.,
  imu_sampling_ratio = 1.,
  landmarks_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 10

return options

launch配置:my_robot_map.launch

xml 复制代码
<launch>
  <!-- <param name="robot_description"
    textfile="$(find cartographer_ros)/urdf/my_robot_2d.urdf" />

  <node name="robot_state_publisher" pkg="robot_state_publisher"
    type="robot_state_publisher" /> -->

  <node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename my_robot.lua"
      output="screen">
    <remap from="scan" to="scan" />
    <remap from="imu" to="imu" />
    <!-- <remap from="odom" to="odom" /> -->
  </node>

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
  <node name="rviz" pkg="rviz" type="rviz" required="true"
      args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
</launch>

源码修改

文件路径:/home/hgrobot/cartographer_ws/src/cartographer_ros/cartographer_ros/cartographer_ros/occupancy_grid_node_main.cc

建图需要取消注释

复制代码
  // 注释不发送地图
  // occupancy_grid_publisher_.publish(*msg_ptr);

重新编译

复制代码
catkin_make_isolated --install --use-ninja

source环境

复制代码
catkin_make_isolated --install --use-ninja

运行并建图

启动底盘和imu:

复制代码
roslaunch castlex_plus_bringup castlex_plus_bringup.launch

启动雷达:

复制代码
roslaunch wj_716_lidar wj.launch

启动建图:

复制代码
roslaunch cartographer_ros my_robot_map.launch

启动键盘控制:

复制代码
roslaunch castlex_keyboard_control keyboard_control.launch

停止接收地图数据:

复制代码
rosservice call /finish_trajectory 0

保存地图:

复制代码
rosservice call /write_state "{filename: '/home/hgrobot/cartographer_ws/src/cartographer_ros/cartographer_ros/map/map.pbstream'}"

将地图转成png:

复制代码
rosrun cartographer_ros cartographer_pbstream_to_ros_map -map_filestem=/home/hgrobot/ws/src/castlex_navigation/maps/map -pbstream_filename=/home/hgrobot/cartographer_ws/src/cartographer_ros/cartographer_ros/map/map.pbstream -resolution=0.05

导航配置

源码修改:

文件路径:/home/hgrobot/cartographer_ws/src/cartographer_ros/cartographer_ros/cartographer_ros/occupancy_grid_node_main.cc

导航需要注释

复制代码
  // 注释不发送地图
  // occupancy_grid_publisher_.publish(*msg_ptr);

launch配置:my_robot_2d_localization.launch

xml 复制代码
<launch>
  <arg name="load_state_filename" default="/home/hgrobot/cartographer_ws/src/cartographer_ros/cartographer_ros/map/map.pbstream"/>

  <node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename my_robot_location.lua
          -load_state_filename $(arg load_state_filename)"
      output="screen">
    <remap from="scan" to="scan" />
    <remap from="imu" to="imu" />
  </node>

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05 " />  <!-- 增加是否纯定位模式参数pure_localization -->

</launch>

lua文件配置:

lua 复制代码
include "my_robot.lua"

TRAJECTORY_BUILDER.pure_localization_trimmer = {
    max_submaps_to_keep = 3,
  }
  POSE_GRAPH.optimize_every_n_nodes =100

return options

启动底盘和imu:

复制代码
roslaunch castlex_plus_bringup castlex_plus_bringup.launch

启动雷达:

复制代码
roslaunch wj_716_lidar wj.launch

启动定位:

注意小车启动位置要和开始位置一样

复制代码
roslaunch cartographer_ros my_robot_2d_localization.launch

启动导航:

复制代码
roslaunch castlex_navigation teb_nav.launch

遇到的问题:

编译错误---解决方法:删除build,重新编译

小车跳变---tf有问题,小车底盘发布的是odom-base_footprint的tf变换,没有发布base_footprint-base_link的变换,move_base设置的是base_link,map,odom。使用的是teb算法。

存在问题:

1.建图和定位切换需要修改源码

2.不能自动重定位

相关推荐
MintonLee复现侠4 天前
记录RK3588的docker中启动rviz2报错
docker·容器·ros·rk3588·rviz·rviz2
Mr.Winter`6 天前
运动规划实战案例 | 基于多源流场(Flow Field)的路径规划(附ROS C++/Python实现)
人工智能·机器人·自动驾驶·ros·ros2·具身智能
Tipriest_9 天前
wstool和git submodule优劣势对比
ros·wstool·git submodule
zylyehuo20 天前
ROS1(20.04 noetic) + PX4 + AirSim
ros·drone
想要成为计算机高手21 天前
11. isaacsim4.2教程-Transform 树与Odometry
人工智能·机器人·自动驾驶·ros·rviz·isaac sim·仿真环境
Zhichao_9723 天前
【ROS1】09-ROS通信机制——参数服务器
ros
想要成为计算机高手24 天前
10. isaacsim4.2教程-RTX Lidar 传感器
数码相机·机器人·ros·仿真·具身智能·vla·isaacsim
城北有个混子24 天前
【机器人】—— 3. ROS 架构 & 文件系统
机器人·ros
江山如画,佳人北望25 天前
Cartographer_ros代码阅读
cartographer
Mr.Winter`1 个月前
轨迹优化 | 基于边界中间值问题(BIVP)的路径平滑求解器(附C++/Python仿真)
人工智能·机器人·自动驾驶·ros·路径规划·数值优化·轨迹优化