ROS交流群
ROS Group
产品服务
Product Service
开源代码库
Github
官网
Official website
技术交流
Technological exchanges
激光雷达
LIDAR
ROS教程
ROS Tourials
深度学习
Deep Learning
机器视觉
Computer Vision

小强ROS机器人教程(19)___NLlinepatrol_planner的简单使用


  • administrators

    小强主页

    随小车主机附带的NLlinepatrol_planner是一个用于视觉导航的全局路径规划器,根据小车输出的视觉轨迹(视觉轨迹文件的获得请参考当前栏目下的帖子),能输出一条连接小车当前坐标和目的坐标的全局路径,下文将通过一个模拟实例来演示它的使用方式。主要思路是:一个python脚本发布虚拟的视觉里程计和相关tf树,一个python脚本给move_base节点发布目标点,最后move_base节点通过调用NLlinepatrol_planner获得一条全局路径并在rviz中显示。

    1.配置NLlinepatrol_planner

    需要提供NLlinepatrol_planner待读取的视觉轨迹文件、轨迹坐标变换需要的变换参数文件,这两文件都应该放在NLlinepatrol_planner下面的data文件夹内,文件名任意,通过配置move_base中的相关参数可以指定NLlinepatrol_planner读取的文件,下文会说明。
    0_1468418651652_1.png

    在上图中,nav1.csv是视觉轨迹文件、TFSettings.txt为变换参数文件(第一行是旋转矩阵的9个元素、数组元素排列顺序为c语言的行排列,第二行为平移向量的xyz分量,第三行为scale因子)

    2.制作move_base的launch文件

    对于本教程,我们已经在nav_test软件包中的launch文件夹内提供了相关的launch文件,名字为xq_move_base_blank_map2.launch,这个launch文件在实际运用时可以作为模板,需要注意的地方请看下图
    0_1468419988004_2.png
    这个launch文件会调用xq_move_base2.launch文件,xq_move_base2.launch文件也在当前目录下,里面的内容如下

    <launch>
    
      <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
        <param name="base_global_planner" value="NLlinepatrol_planner/NLlinepatrolPlanner"/>
        <rosparam file="$(find nav_test)/config/NLlinepatrol/costmap_common_params.yaml" command="load" ns="global_costmap" />
        <rosparam file="$(find nav_test)/config/NLlinepatrol/costmap_common_params.yaml" command="load" ns="local_costmap" />
        <rosparam file="$(find nav_test)/config/NLlinepatrol/local_costmap_params.yaml" command="load" />
        <rosparam file="$(find nav_test)/config/NLlinepatrol/global_costmap_params.yaml" command="load" />
        <rosparam file="$(find nav_test)/config/NLlinepatrol/base_local_planner_params.yaml" command="load" />
        <rosparam file="$(find nav_test)/config/NLlinepatrol/base_global_planner_params.yaml" command="load" />
      </node>
    
    </launch>
    
    通过上述内容,发现通过设置base_global_planner参数值来指定全局路径规划器为NLlinepatrol_planner,还可以看出move_base的其它参数配置文件放在nav_test软件包内的config/NLlinepatrol路径内

    0_1468420510330_3.png

    对于上图,我们需要更改的文件是base_global_planner_params.yaml,因为这个文件里的内容对应NLlinepatrol_planner运行时实际加载的参数,默认内容如下
    NLlinepatrolPlanner:
        DumpFileName: AnnDump.sav
        strTFParsFile: TFSettings.txt
        TxtFileName: nav1.csv
        ANN_Dump_Bool: false
        connect_distance: 0.3
    
    TxtFileName是加载的视觉轨迹文件名,strTFParsFile是加载的变换参数文件名,connect_distance设置视觉轨迹文件中连通点之间的最大距离(坐标变换后两个点之间的距离小于该值就认为这两点之间没有障碍物,可以直接连接),ANN_Dump_Bool值为false表示从txt文件中加载轨迹和变换参数、如果为true则从DumpFileName参数指定的dump文件加载(多次使用同一个视觉轨迹文件时,第二次以后从dump文件启动可以加速)

    3.配置完成开始使用

    A.因为我们这次是虚拟运行,发布的一些topic是没有实际意义的但是和小强默认ROS驱动冲突,所以现在需要停止所有ROS运行实例
    sudo service startup stop
    roscore
    
    B.启动虚拟topic和小强模型文件
    rosrun orb_init temp.py //发布odom
    roslaunch xiaoqiang_udrf xiaoqiang_udrf.launch //启动模型
    
    C.启动上文制作的xq_move_base_blank_map2.launch文件
    roslaunch nav_test xq_move_base_blank_map2.launch
    
    D.启动rviz,并打开ros/src/nav_test/config/nav_xq2.rviz配置文件
    rviz
    
    E.启动虚拟goal发布节点(基于惯性导航中的squre.py修改而来)
    rosrun nav_test NLlinepatrol.py
    

    4.现在rviz中就已经出现目标全局路径轨迹了(绿线),想测试其它goal目标点,请自行修改NLlinepatrol.py中相关代码

    0_1468422345670_last.png

    小强主页
    返回目录