ROS Group 产品服务
Product Service 开源代码库
Github 官网
Official website 技术交流
Technological exchanges 激光雷达
LIDAR ROS教程
ROS Tourials 深度学习
Deep Learning 机器视觉
Computer Vision
Xiaoqiang tutorial (19) usage of NLlinepatrol_planner
-
The
NLlinepatrol_planner
included with Xiaoqiang’s host is a global path planner for visual navigation. According to Xiaoqiang’s output visual trajectory (for visual trajectory files, please refer to this post), it can output a global path link to Xiaoqiang’s current position and destination target point. It will be demonstrated below using a simulation example. The main idea is: a python script publishes virtual visual odometers and related tf trees. Another python script publishes target points to themove_base
node. Finally, themove_base
node obtains a global path by callingNLlinepatrol_planner
and displays it in rviz.1. Configure NLlinepatrol_planner
To use
NLlinepatrol_planner
, you need to provide visual trajectory file thatNLlinepatrol_planner
will read and (transformation parameters) file that is required for the coordinate transformation of the track, both files should be placed in the data folder underNLlinepatrol_planner
, the file name is arbitrary, by configuring the related parameters inmove_base
You can specify the file thatNLlinepatrol_planner
reads, as explained below.In the figure above, nav1.csv is the visual trajectory file and TFSettings.txt is the transformation parameter file (the first row is the 9 elements of the rotation matrix, the array elements are arranged in the row of the c language, and the second row is the xyz of the translation vector. Components, the third one is the scale factor)
2.Make a move_base launch file
In this tutorial, we have provided the relevant launch file in the launch folder of the
nav_test
package. The file name isxq_move_base_blank_map2.launch
. This launch file can be used as a template during actual use. Please pay attention to the following figure.The launch file will call the
xq_move_base2.launch
file. Thexq_move_base2.launch
file is also in the current directory. The contents are as follows:<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>
Through the above, it is found that by setting the value of the
base_global_planner
parameter to specify the global path planner asNLlinepatrol_planner
, it can also be seen that the other parameter configuration files of move_base are stored in theconfig/NLlinepatrol
path in the nav_test package.For the above image, the file we need to change is
base_global_planner_params.yaml
, because the contents of this file correspond to the parameters actually loaded by theNLlinepatrol_planner
runtime. The default content is as follows:NLlinepatrolPlanner: DumpFileName: AnnDump.sav strTFParsFile: TFSettings.txt TxtFileName: nav1.csv ANN_Dump_Bool: false connect_distance: 0.3
TxtFileName specifies the name of the loaded visual track file, strTFParsFile specifies the name of the loaded transformation parameter file, and connect_distance sets the maximum distance between the connected points in the visual track file. (The distance between two points after the coordinate transformation is smaller than the value is considered as There is no obstacle between the two points, you can directly connect), ANN_Dump_Bool value is false to load the trajectory and transformation parameters from the txt file, if it is true then load from the dump file specified by the DumpFileName parameter (When using the same visual track file multiple times , start from the dump file after the second time can be accelerated)
3. Start using after configuration
A. Because we are virtual running this time, some of the published topics are of no practical significance but conflict with Xiaoqiang’s default ROS driver. So now we need to stop all ROS running instances.
sudo service startup stop roscore
B. Start virtual topic and Xiaoqiang model files
rosrun orb_init temp.py // Publish odom roslaunch xiaoqiang_udrf xiaoqiang_udrf.launch // Start the model
C. Launch the xq_move_base_blank_map2.launch file produced above
roslaunch nav_test xq_move_base_blank_map2.launch
D. Start rviz and open the ros/src/nav_test/config/nav_xq2.rviz configuration file
rviz
E. Launch virtual goal publishing node (based on squre.py modification in inertial navigation)
rosrun nav_test NLlinepatrol.py
4. Now that the target global path trajectory (green line) has appeared in rviz and you want to test other goal targets, modify the code in NLlinepatrol.py.