[新增功能](master): 增加AP1导航套件二次开发RTK文档

master
杨明 2022-09-28 17:14:12 +08:00
parent 336b750077
commit 3b4e8f3966
6 changed files with 272 additions and 161 deletions

View File

@ -240,8 +240,12 @@
"uri": "version_two/development/vslamintro"
},
{
"name": "定位循迹",
"name": "定位标签循迹",
"uri": "version_two/development/locationintro"
},
{
"name": "RTK循迹",
"uri": "version_two/development/rtkintro"
}
]
},

View File

@ -1,8 +1,9 @@
# AutolaborOS
# AutolaborOS
## 简介
AutolaborOS 是由 Autolabor 推出的免费开源机器人操作系统,基于 ubuntu18.04 与 ROS Melodic 开发而成,包含 ROS Melodic 、常用 ROS包Cartographer、Gmapping、Navigation ···机器人底盘与传感器驱动包机器人仿真应用以及激光SLAM导航、自动巡迹导航应用等。
AutolaborOS 是由 Autolabor 推出的免费开源机器人操作系统,基于 ubuntu18.04 与 ROS Melodic 开发而成,包含 ROS Melodic 、常用
ROS包Cartographer、Gmapping、Navigation ···机器人底盘与传感器驱动包机器人仿真应用以及激光SLAM导航、自动巡迹导航应用等。
解决了繁琐的 ROS 环境安装问题节省时间成本降低技术壁垒。使用该系统学习ROS、开发机器人、实现自己的算法做一些有趣的事情。
@ -12,10 +13,9 @@ AutolaborOS 是由 Autolabor 推出的免费开源机器人操作系统,基于
OS在AP1上已经实现了机器人自主导航2D/3D SLAM 单目标/多目标)、自动循迹、远程遥控等功能。
## 源码说明
以下内容基于AutolaborOS 2.2.4
以下内容基于AutolaborOS 22.07
```
catkin_ws
@ -24,122 +24,130 @@ catkin_ws
catkin_ws/src/driver/
├── car
   ├── autolabor_canbus_driver //PM1底盘驱动
   └── autolabor_pro1_driver //AP1底盘驱动
├── autolabor_canbus_driver //PM1底盘驱动
└── autolabor_pro1_driver //AP1底盘驱动
├── depth_camera
   ├── iai_kinect2-master //kinect V2 相机驱动
   └── pico_zense_driver //Vzense DCAM710 相机驱动
├── iai_kinect2-master //kinect V2 相机驱动
└── pico_zense_driver //Vzense DCAM710 相机驱动
├── imu
   ├── ah100b //ah100b,ah200c 惯导驱动
   ├── rviz_imu_plugin //rviz 惯导可视化插件,显示惯导图像
   └── tl740d //tl740d 转角仪驱动
├── ah100b //ah100b,ah200c 惯导驱动
├── rviz_imu_plugin //rviz 惯导可视化插件,显示惯导图像
└── tl740d //tl740d 转角仪驱动
├── joystick
   └── joystick_drivers // 罗技F710 遥控手柄驱动
└── joystick_drivers // 罗技F710 遥控手柄驱动
├── lidar
│   ├── rplidar_ros //思岚A2 雷达驱动
│   ├── rslidar //速腾RS16 雷达驱动
│   ├── urg_node //北洋Hokuyo UST-10LX 雷达驱动
│   └── wr_fslidar // 砝石FS-D10 雷达驱动
│ ├── ldlidar_stl_ros //乐动19 雷达驱动
│ ├── rplidar_ros //思岚A2 雷达驱动
│ ├── rslidar //速腾RS16、RS-Helios雷达驱动
│ ├── urg_node //北洋Hokuyo UST-10LX 雷达驱动
│ └── wr_fslidar // 砝石FS-D10 雷达驱动
└── location
└── al_rtk_ros_driver // RTK570 接收机驱动
└── marvelmind // marvelmind 定位标签驱动
catkin_ws/src/launch/
├── autolabor_navigation_launch //导航launch
│   ├── launch
│   │   ├── real_environment //实车launch
│   │   │   ├── first_generation_base.launch //单雷达版本-传感器驱动
│   │   │   ├── first_generation_mapping.launch //单雷达版本-建图
│   │   │   ├── first_generation_navigation.launch //单雷达版本-导航
│   │   │   ├── second_generation_advanced_base.launch //双雷达版本-传感器驱动(含定位标签)
│   │   │   ├── second_generation_basic_base.launch //双雷达版本-传感器驱动
│   │   │   ├── second_generation_mapping.launch //双雷达版本-建图
│   │   │   ├── second_generation_multigoal_navigation.launch //双雷达版本-多点导航
│   │   │   ├── second_generation_navigation.launch //双雷达版本-导航
│   │   │   ├── second_generation_tracking.launch //双雷达版本-循迹
│   │   │   ├── third_generation_base.launch //多线雷达版本-传感器驱动
│   │   │   ├── third_generation_cartographer_3d.launch //多线雷达版本-建图
│   │   │   └── third_generation_navigation_3d.launch //多线雷达版本-导航
│   │   └── simulated_environment //模拟器launch
│   │   ├── common_stage_simulation.launch //模拟场景地图
│   │   ├── first_generation_base_simulation.launch
│   │   ├── first_generation_mapping_simulation.launch
│   │   ├── first_generation_navigation_simulation.launch
│   │   ├── second_generation_advanced_base_simulation.launch
│   │   ├── second_generation_basic_base_simulation.launch
│   │   ├── second_generation_driver_simulation.launch
│   │   ├── second_generation_mapping_simulation.launch
│   │   ├── second_generation_multicar_following_simulation.launch //多车跟随
│   │   ├── second_generation_multicar_navigation_simulation.launch //多车导航
│   │   ├── second_generation_multigoal_navigation_simulation.launch //多目标导航
│   │   ├── second_generation_navigation_simulation.launch
│   │   └── second_generation_tracking_simulation.launch
│   ├── map //建图保存的地图文件
│   │   ├── map_3d.pbstream //3d slam 地图文件,用于定位,不可修改(保存地图后生成)
│   │   ├── map_3d.pgm //3d slam 地图文件,用于导航,可修改(保存地图后生成)
│   │   ├── map_3d.yaml //map_3d.pgm 的解释文件(保存地图后生成)
│   │   ├── map.pbstream //2d slam 地图文件,用于定位导航,不可修改
│   │   ├── map_simulation.pbstream //模拟器地图文件
│   │   ├── simulation_stage.png //模拟器环境地图
│   │   └── simulation_stage.yaml //simulation_stage.png 的解释文件
│   ├── params //配置文件
│   │   ├── cartographer
│   │   │   ├── first_generation_location.lua //单雷达版本-定位
│   │   │   ├── first_generation_mapping.lua //单雷达版本-建图
│   │   │   ├── map_builder.lua //cartographer 配置文件
│   │   │   ├── map_builder_server.lua //cartographer 配置文件
│   │   │   ├── pose_graph.lua //cartographer 配置文件
│   │   │   ├── second_generation_location.lua //双雷达版本-定位
│   │   │   ├── second_generation_mapping.lua //双雷达版本-建图
│   │   │   ├── second_generation_multicar_location.lua //双雷达版本-多车定位(模拟器)
│   │   │   ├── third_generation_location.lua //多线雷达版本-定位
│   │   │   ├── third_generation_mapping.lua //多线雷达版本-建图
│   │   │   ├── trajectory_builder_2d.lua //cartographer 配置文件
│   │   │   ├── trajectory_builder_3d.lua //cartographer 配置文件
│   │   │   └── trajectory_builder.lua //cartographer 配置文件
│   │   ├── common
│   │   │   ├── back_lidar_config.yaml //后雷达过滤配置文件
│   │   │   └── front_lidar_config.yaml //前雷达过滤配置文件
│   │   └── navigation
│   │   ├── costmap //代价地图配置文件
│   │   │   ├── 3d_global_costmap_params.yaml //3d slam 全局代价地图
│   │   │   ├── 3d_local_costmap_params.yaml //3d slam 局部代价地图
│   │   │   ├── one_laser_global_costmap_params.yaml //单雷达版本-全局代价地图
│   │   │   ├── one_laser_local_costmap_params.yaml //单雷达版本-局部代价地图
│   │   │   ├── two_laser_global_costmap_params_for_tracking.yaml //双雷达版本-循迹-全局代价地图
│   │   │   ├── two_laser_global_costmap_params.yaml //双雷达版本-全局代价地图
│   │   │   └── two_laser_local_costmap_params.yaml //双雷达版本-局部代价地图
│   │   ├── global_planer //全局规划配置文件
│   │   │   ├── global_planner_params.yaml //用于导航
│   │   │   ├── navfn_params.yaml //用于多车(模拟器)
│   │   │   └── tracking_planner_params.yaml //用于循迹
│   │   ├── local_planer //局部规划配置文件
│   │   │   ├── navigation_teb_local_planner_params.yaml //用于导航
│   │   │   └── tracking_teb_local_planner_params.yaml //用于循迹
│   │   └── move_base //ROS Navigation 配置文件
│   │   ├── navigation_move_base.yaml //用于导航
│   │   └── tracking_move_base.yaml //用于循迹
│   └── rviz //rviz配置文件
│   ├── 3d_mapping.rviz //3d slam-建图
│   ├── 3d_navigation.rviz //3d slam-导航
│   ├── first_generation_create_map.rviz //单雷达版本-建图
│   ├── first_generation_navigation.rviz //单雷达版本-导航
│   ├── second_generation_create_map.rviz //双雷达版本-建图
│   ├── second_generation_multicar_navigation.rviz //双雷达版本-多车导航(模拟器)
│   ├── second_generation_multigoal_navigation.rviz //双雷达版本-多点导航
│   ├── second_generation_navigation.rviz //双雷达版本-导航
│   └── second_generation_tracking.rviz //双雷达版本-循迹
│ ├── launch
│ │ ├── real_environment //实车launch
│ │ │ ├── first_generation_base.launch //单雷达版本-传感器驱动
│ │ │ ├── first_generation_mapping.launch //单雷达版本-建图
│ │ │ ├── first_generation_navigation.launch //单雷达版本-导航
│ │ │ ├── rtk_tracking_basic_base.launch//RTK版本-传感器驱动
│ │ │ ├── rtk_tracking.launch //RTK版本-循迹
│ │ │ ├── second_generation_advanced_base.launch //双雷达版本-传感器驱动(含定位标签)
│ │ │ ├── second_generation_basic_base.launch //双雷达版本-传感器驱动
│ │ │ ├── second_generation_mapping.launch //双雷达版本-建图
│ │ │ ├── second_generation_multigoal_navigation.launch //双雷达版本-多点导航
│ │ │ ├── second_generation_navigation.launch //双雷达版本-导航
│ │ │ ├── second_generation_tracking.launch //双雷达版本-循迹
│ │ │ ├── third_generation_base.launch //多线雷达版本-传感器驱动
│ │ │ ├── third_generation_cartographer_3d.launch //多线雷达版本-建图
│ │ │ └── third_generation_navigation_3d.launch //多线雷达版本-导航
│ │ └── simulated_environment //模拟器launch
│ │ ├── common_stage_simulation.launch //模拟场景地图
│ │ ├── first_generation_base_simulation.launch
│ │ ├── first_generation_mapping_simulation.launch
│ │ ├── first_generation_navigation_simulation.launch
│ │ ├── second_generation_advanced_base_simulation.launch
│ │ ├── second_generation_basic_base_simulation.launch
│ │ ├── second_generation_driver_simulation.launch
│ │ ├── second_generation_mapping_simulation.launch
│ │ ├── second_generation_multicar_following_simulation.launch //多车跟随
│ │ ├── second_generation_multicar_navigation_simulation.launch //多车导航
│ │ ├── second_generation_multigoal_navigation_simulation.launch //多目标导航
│ │ ├── second_generation_navigation_simulation.launch
│ │ └── second_generation_tracking_simulation.launch
│ ├── map //建图保存的地图文件
│ │ ├── map_3d.pbstream //3d slam 地图文件,用于定位,不可修改(保存地图后生成)
│ │ ├── map_3d.pgm //3d slam 地图文件,用于导航,可修改(保存地图后生成)
│ │ ├── map_3d.yaml //map_3d.pgm 的解释文件(保存地图后生成)
│ │ ├── map.pbstream //2d slam 地图文件,用于定位导航,不可修改
│ │ ├── map_simulation.pbstream //模拟器地图文件
│ │ ├── simulation_stage.png //模拟器环境地图
│ │ └── simulation_stage.yaml //simulation_stage.png 的解释文件
│ ├── params //配置文件
│ │ ├── cartographer
│ │ │ ├── first_generation_location.lua //单雷达版本-定位
│ │ │ ├── first_generation_mapping.lua //单雷达版本-建图
│ │ │ ├── map_builder.lua //cartographer 配置文件
│ │ │ ├── map_builder_server.lua //cartographer 配置文件
│ │ │ ├── pose_graph.lua //cartographer 配置文件
│ │ │ ├── second_generation_location.lua //双雷达版本-定位
│ │ │ ├── second_generation_mapping.lua //双雷达版本-建图
│ │ │ ├── second_generation_multicar_location.lua //双雷达版本-多车定位(模拟器)
│ │ │ ├── third_generation_location.lua //多线雷达版本-定位
│ │ │ ├── third_generation_mapping.lua //多线雷达版本-建图
│ │ │ ├── trajectory_builder_2d.lua //cartographer 配置文件
│ │ │ ├── trajectory_builder_3d.lua //cartographer 配置文件
│ │ │ └── trajectory_builder.lua //cartographer 配置文件
│ │ ├── common
│ │ │ ├── back_lidar_config.yaml //后雷达过滤配置文件
│ │ │ └── front_lidar_config.yaml //前雷达过滤配置文件
│ │ └── navigation
│ │ ├── costmap //代价地图配置文件
│ │ │ ├── 3d_global_costmap_params.yaml //3d slam 全局代价地图
│ │ │ ├── 3d_local_costmap_params.yaml //3d slam 局部代价地图
│ │ │ ├── one_laser_global_costmap_params.yaml //单雷达版本-全局代价地图
│ │ │ ├── one_laser_local_costmap_params.yaml //单雷达版本-局部代价地图
│ │ │ ├── two_laser_global_costmap_params_for_tracking.yaml //双雷达版本-循迹-全局代价地图
│ │ │ ├── two_laser_global_costmap_params.yaml //双雷达版本-全局代价地图
│ │ │ └── two_laser_local_costmap_params.yaml //双雷达版本-局部代价地图
│ │ ├── global_planer //全局规划配置文件
│ │ │ ├── global_planner_params.yaml //用于导航
│ │ │ ├── navfn_params.yaml //用于多车(模拟器)
│ │ │ └── tracking_planner_params.yaml //用于循迹
│ │ ├── local_planer //局部规划配置文件
│ │ │ ├── navigation_teb_local_planner_params.yaml //用于导航
│ │ │ └── tracking_teb_local_planner_params.yaml //用于循迹
│ │ └── move_base //ROS Navigation 配置文件
│ │ ├── navigation_move_base.yaml //用于导航
│ │ └── tracking_move_base.yaml //用于循迹
│ └── rviz //rviz配置文件
│ ├── 3d_mapping.rviz //3d slam-建图
│ ├── 3d_navigation.rviz //3d slam-导航
│ ├── first_generation_create_map.rviz //单雷达版本-建图
│ ├── first_generation_navigation.rviz //单雷达版本-导航
│ ├── second_generation_create_map.rviz //双雷达版本-建图
│ ├── second_generation_multicar_navigation.rviz //双雷达版本-多车导航(模拟器)
│ ├── second_generation_multigoal_navigation.rviz //双雷达版本-多点导航
│ ├── second_generation_navigation.rviz //双雷达版本-导航
│ └── second_generation_tracking.rviz //双雷达版本-循迹
└── autolabor_test_launch //测试
├── launch
│   ├── car_test.launch //键盘遥控
│   ├── fslidar_test.launch //砝石FS-D10双雷达测试
│   ├── imu_test.launch //惯导测试
│   ├── kinect2_test.launch //kinect V2测试
│   ├── robot_calibration.launch //AP1标定
│   └── tag_test.launch //定位标签测试
│ ├── car_test.launch //键盘遥控
│ ├── 2dlidar_test.launch //单线激光雷达测试
│ ├── 3dlidar_test.launch //多线激光雷达测试
│ ├── imu_test.launch //惯导测试
│ ├── kinect2_test.launch //深度相机测试
│ ├── robot_calibration.launch //AP1标定
│ └── rtk_test.launch //RTK测试
│ └── tag_test.launch //定位标签测试
└── rviz //rviz配置文件
├── 3dlidar.rviz //多线激光雷达测试
├── car.rviz //键盘遥控
├── fslidar.rviz //砝石FS-D10双雷达测试
├── fslidar.rviz //单线雷达测试
├── robot_calibration.rviz //AP1标定
└── rtk_test.rviz //RTK测试
└── tag.rviz //定位标签测试
@ -159,7 +167,7 @@ catkin_ws/src/navigation/ //ROS Navigation 源码
├── dwa_local_planner //dwa局部规划
├── fake_localization //OS中未使用
├── global_planner //全局规划
├── location_fusion //定位融合(定位标签+里程计)
├── location_fusion //定位融合(定位标签/RTK+里程计)
├── loop_path_planner //循迹全局规划
├── map_server //地图服务
├── move_base //movebase
@ -170,8 +178,8 @@ catkin_ws/src/navigation/ //ROS Navigation 源码
├── navigation //ROS Navigation元
├── path_rviz_plugin //循迹rviz插件功能按钮组
├── path_server //用于循迹中录制路线
   ├── path_data
   │   ├── default_path.path //循迹中保存的路径数据
├── path_data
├── default_path.path //循迹中保存的路径数据
├── record_path_planner //循迹全局规划
├── rotate_recovery //恢复行为
├── teb_local_planner //局部规划
@ -180,20 +188,20 @@ catkin_ws/src/navigation/ //ROS Navigation 源码
catkin_ws/src/simulation/ //模拟器
├── autolabor_description //机器人模型
   ├── launch
   │   ├── display_autolabor_mini.launch
   │   └── display_autolabor_pro1.launch
   ├── meshes
   │   ├── autolabor_mini.stl
   │   ├── pro1_body_color.dae //AP1模型文件-主体
   │   └── pro1_wheel_color.dae //AP1模型文件-轮子
   ├── rviz
   │   └── urdf.rviz
   └── urdf
   ├── autolabor_mini.urdf
   ├── first_generation_model.xacro //单雷达版本-机器人描述(类似urdf)
   ├── second_generation_model.xacro //双雷达版本-机器人描述(类似urdf)
   └── third_generation_model.xacro //多线雷达版本-机器人描述(类似urdf)
├── launch
├── display_autolabor_mini.launch
└── display_autolabor_pro1.launch
├── meshes
├── autolabor_mini.stl
├── pro1_body_color.dae //AP1模型文件-主体
└── pro1_wheel_color.dae //AP1模型文件-轮子
├── rviz
└── urdf.rviz
└── urdf
├── autolabor_mini.urdf
├── first_generation_model.xacro //单雷达版本-机器人描述(类似urdf)
├── second_generation_model.xacro //双雷达版本-机器人描述(类似urdf)
└── third_generation_model.xacro //多线雷达版本-机器人描述(类似urdf)
├── autolabor_simulation_base //机器人底盘模拟
├── autolabor_simulation_lidar //雷达模拟
├── autolabor_simulation_location //定位标签模拟
@ -215,35 +223,35 @@ catkin_ws/src/tool/
script //执行脚本
├── 3d_suit //多线雷达版本
   ├── create_map_start
   ├── create_map_stop
   ├── navigation_start
   └── navigation_stop
├── create_map_start
├── create_map_stop
├── navigation_start
└── navigation_stop
├── box_suit //单雷达版本
   ├── create_map_start
   ├── create_map_stop
   ├── navigation_start
   └── navigation_stop
├── create_map_start
├── create_map_stop
├── navigation_start
└── navigation_stop
├── common
   ├── add_keyboard_udev //用于键盘控制,加键盘权限
   └── rebuild //工作空间编译脚本
├── add_keyboard_udev //用于键盘控制,加键盘权限
└── rebuild //工作空间编译脚本
├── simulation //模拟器
   ├── create_map_start
   ├── create_map_stop
   ├── navigation_start
   ├── navigation_stop
   ├── tracking_start
   └── tracking_stop
├── create_map_start
├── create_map_stop
├── navigation_start
├── navigation_stop
├── tracking_start
└── tracking_stop
├── test //测试
   ├── car_test
   ├── fslidar_test
   ├── imu_test
   ├── kinect2_test
   ├── pico_test
   ├── robot_calibration
   ├── rplidar_test
   ├── rslidar_test
   └── tag_test
├── car_test
├── fslidar_test
├── imu_test
├── kinect2_test
├── pico_test
├── robot_calibration
├── rplidar_test
├── rslidar_test
└── tag_test
└── track_suit //双雷达版本
├── create_map_start
├── create_map_stop
@ -251,4 +259,4 @@ script //执行脚本
├── navigation_stop
├── tracking_start //开始循迹
└── tracking_stop //停止循迹
```
```

Binary file not shown.

After

Width:  |  Height:  |  Size: 44 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 175 KiB

View File

@ -1,4 +1,4 @@
# 定位循迹
# 定位标签循迹
## 目录
@ -39,15 +39,15 @@
![](imgs/software_intro_3.jpg)
| 步骤 | 输入数据 | 操作 | 输出数据 | 使用ROS包 |
|--|--|--|--|--|
|1 | | Dashboard部署定位地图 | 定位数据(车载定位标签坐标)| marvelmind驱动包(catkin_ws\src\driver\location\marvelmind)|
|2 | 里程计数据 定位数据 | 定位融合| 当前机器人在环境中的位姿 | location_fusion(catkin_ws\src\navigation\location_fusion)|
|3| 当前机器人位姿| 控制机器人运动,录制路径| 路径数据 |path_server(catkin_ws\src\navigation\path_server)|
|4| 路径数据| 读取录制的路径数据,执行循迹操作 | 目标机器人位姿 |path_server(catkin_ws\src\navigation\path_server) [move_base](http://wiki.ros.org/move_base/)|
|5| 当前机器人位姿 目标机器人位姿| 根据机器人当前位姿,进行全局规划路线| 路径数据(初步预估导航路线) |[global_planner(dijkstra) ](http://wiki.ros.org/global_planner)|
|6| 路径数据 前雷达数据 后雷达数据 | 根据规划路径开始导航,进行过程中随着实际环境、障碍物变化,进行局部路径规划,实时避障| 局部路径规划 避障 |[costmap_2d ](http://wiki.ros.org/cost_map)[teb_local_planner](http://wiki.ros.org/teb_local_planner)|
|7| 速度信息 /cmd_vel | 向底层发送速度命令 | |[move_base](http://wiki.ros.org/move_base/)|
| 步骤 | 输入数据 | 操作 | 输出数据 | 使用ROS包 |
|-----|------------------|--------------------------------------------|----------------|-------------------------------------------------------------------------------------------------------|
| 1 | | Dashboard部署定位地图 | 定位数据(车载定位标签坐标) | marvelmind驱动包(catkin_ws\src\driver\location\marvelmind) |
| 2 | 里程计数据 定位数据 | 定位融合 | 当前机器人在环境中的位姿 | location_fusion(catkin_ws\src\navigation\location_fusion) |
| 3 | 当前机器人位姿 | 控制机器人运动,录制路径 | 路径数据 | path_server(catkin_ws\src\navigation\path_server) |
| 4 | 路径数据 | 读取录制的路径数据,执行循迹操作 | 目标机器人位姿 | path_server(catkin_ws\src\navigation\path_server) [move_base](http://wiki.ros.org/move_base/) |
| 5 | 当前机器人位姿 目标机器人位姿 | 根据机器人当前位姿,进行全局规划路线 | 路径数据(初步预估导航路线) | [global_planner(dijkstra) ](http://wiki.ros.org/global_planner) |
| 6 | 路径数据 前雷达数据 后雷达数据 | 根据规划路径开始导航,进行过程中随着实际环境、障碍物变化,进行局部路径规划,实时避障 | 局部路径规划 避障 | [costmap_2d ](http://wiki.ros.org/cost_map)[teb_local_planner](http://wiki.ros.org/teb_local_planner) |
| 7 | 速度信息 /cmd_vel | 向底层发送速度命令 | | [move_base](http://wiki.ros.org/move_base/) |
定位循迹 launch配置示例
@ -86,4 +86,4 @@
<rosparam file="$(find autolabor_navigation_launch)/params/navigation/local_planer/tracking_teb_local_planner_params.yaml" command="load" ns="TebLocalPlannerROS"/>
</node>
```
```

View File

@ -0,0 +1,99 @@
# RTK循迹
## 目录
* 功能介绍
* 传感器介绍
* 实现原理
## 功能介绍
RTK循迹是机器人循着用户提前录好的轨迹自主行走行走过程中机器人能够自动躲避障碍物自动规划路线达到目标点。
RTK循迹要求配置好RTK接收机然后控制车端完成循迹。
RTK接收机的数据与里程计的数据融合定位得到AP1在环境中的坐标点控制AP1运动边走边记录当前坐标点的位置将这些坐标点记录为文件保存下来得到路径文件。
在开始循迹的时候程序加载路径文件RTK接收机定位数据与里程计融合定位匹配路径数据机器人按照指定路径行走。
## 传感器介绍
RTK循迹 用到的传感器有:
* 单线激光雷达x2安装在AP1前后底部
* RTK接收机安装在AP1顶板上
* 编码器/轮速里程计x2安装在车体内部前侧
![](imgs/rtk_intro_1.png)
## 实现原理
![](imgs/rtk_intro_2.png)
| 步骤 | 输入数据 | 操作 | 输出数据 | 使用ROS包 |
|-----|------------------|--------------------------------------------|----------------|-------------------------------------------------------------------------------------------------------|
| 1 | | RTK接收机 | 定位数据 | marvelmind驱动包(catkin_ws\src\driver\location\al_rtk_ros_driver) |
| 2 | 里程计数据 定位数据 | 定位融合 | 当前机器人在环境中的位姿 | location_fusion(catkin_ws\src\navigation\location_fusion) |
| 3 | 当前机器人位姿 | 控制机器人运动,录制路径 | 路径数据 | path_server(catkin_ws\src\navigation\path_server) |
| 4 | 路径数据 | 读取录制的路径数据,执行循迹操作 | 目标机器人位姿 | path_server(catkin_ws\src\navigation\path_server) [move_base](http://wiki.ros.org/move_base/) |
| 5 | 当前机器人位姿 目标机器人位姿 | 根据机器人当前位姿,进行全局规划路线 | 路径数据(初步预估导航路线) | [global_planner(dijkstra) ](http://wiki.ros.org/global_planner) |
| 6 | 路径数据 前雷达数据 后雷达数据 | 根据规划路径开始导航,进行过程中随着实际环境、障碍物变化,进行局部路径规划,实时避障 | 局部路径规划 避障 | [costmap_2d ](http://wiki.ros.org/cost_map)[teb_local_planner](http://wiki.ros.org/teb_local_planner) |
| 7 | 速度信息 /cmd_vel | 向底层发送速度命令 | | [move_base](http://wiki.ros.org/move_base/) |
定位循迹 launch配置示例
```
<!-- RTK定位驱动 -->
<node pkg="al_rtk_ros_driver" type="al_rtk_ros_driver" name="al_ros_driver">
<remap from="/al_ros_driver/location_pos" to="location_pos"/>
<param name="map_frame" value="map"/>
<param name="serial_device" value="/dev/box_3"/>
<param name="badurate" value="115200"/>
<param name="domain" value="rtk.ntrip.qxwz.com"/>
<param name="account" value="qxnsv0012"/>
<param name="password" value="7fd7069"/>
<param name="publish_pos_fix_only" value="true"/>
<param name="auto_use_first_fix_as_enu_origin" value="true" />
<param name="origin_config_file" value="$(find autolabor_navigation_launch)/params/rtk_tracking_enu_origin.json"/>
</node>
<!-- 定位与里程计定位融合 -->
<node name="location_fusion" pkg="location_fusion" type="simple_fusion">
<param name="map_frame" value="map"/>
<param name="odom_frame" value="odom"/>
<param name="buffer_size" value="50"/>
<param name="tag_frame" value="lidar_front" />
<param name="distance_interval" value="0.1"/>
<param name="rate" value="200"/>
</node>
<!-- 录制路径 -->
<node name="path_saver" pkg="path_server" type="record_path_node">
<param name="map_frame" value="map"/>
<param name="base_link_frame" value="base_link"/>
<param name="odom_topic" value="odom"/>
<param name="distance_interval" value="0.2"/>
</node>
<!-- 加载路径 -->
<node name="path_loader" pkg="path_server" type="load_path_node">
<param name="map_frame" value="map"/>
<param name="path_file" value="default_path"/>
</node>
<!-- 导航模块 -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find autolabor_navigation_launch)/params/navigation/move_base/rtk_tracking_move_base.yaml" command="load" />
<rosparam file="$(find autolabor_navigation_launch)/params/navigation/costmap/two_laser_global_costmap_params_for_tracking.yaml" command="load" ns="global_costmap"/>
<rosparam file="$(find autolabor_navigation_launch)/params/navigation/costmap/two_laser_local_costmap_params.yaml" command="load" ns="local_costmap"/>
<rosparam file="$(find autolabor_navigation_launch)/params/navigation/global_planer/tracking_planner_params.yaml" command="load" ns="LoopPathPlanner"/>
<rosparam file="$(find autolabor_navigation_launch)/params/navigation/local_planer/tracking_teb_local_planner_params.yaml" command="load" ns="TebLocalPlannerROS"/>
</node>
```