navgationkit-docs-sphinx/source/version_two/development/rtkintro.md

5.7 KiB
Raw Blame History

RTK循迹

目录

  • 功能介绍
  • 传感器介绍
  • 实现原理

功能介绍

RTK循迹是机器人循着用户提前录好的轨迹自主行走行走过程中机器人能够自动躲避障碍物自动规划路线达到目标点。

RTK循迹要求配置好RTK接收机然后控制车端完成循迹。

RTK接收机的数据与里程计的数据融合定位得到AP1在环境中的坐标点控制AP1运动边走边记录当前坐标点的位置将这些坐标点记录为文件保存下来得到路径文件。

在开始循迹的时候程序加载路径文件RTK接收机定位数据与里程计融合定位匹配路径数据机器人按照指定路径行走。

传感器介绍

RTK循迹 用到的传感器有:

  • 单线激光雷达x2安装在AP1前后底部
  • RTK接收机安装在AP1顶板上
  • 编码器/轮速里程计x2安装在车体内部前侧

实现原理

步骤 输入数据 操作 输出数据 使用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
5 当前机器人位姿 目标机器人位姿 根据机器人当前位姿,进行全局规划路线 路径数据(初步预估导航路线) global_planner(dijkstra)
6 路径数据 前雷达数据 后雷达数据 根据规划路径开始导航,进行过程中随着实际环境、障碍物变化,进行局部路径规划,实时避障 局部路径规划 避障 costmap_2d teb_local_planner
7 速度信息 /cmd_vel 向底层发送速度命令 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>