CARLA_autoware的配置流程(四)在 CARLA 中生成自定义高精地图
2023年 09月 20日 星期三 08:42:51 CST
此文件记录了将 CARLA 仿真的 velodyne 的 /points_raw 激光雷达数据的录制与 ndt_mapping 高精地图创建
检查激光雷达的数据
首先检查激光雷达的数据,看是否能用于 ndt_mapping 的创建
# 启动 carla 仿真
cd ~/CARLA_0.9.11
bash CarlaUE4.sh -prefernvidia
# 启动ROS连接桥
roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch town:=town01
# 启动话题转发节点
roslaunch topic_forwarding autoware_carla.launch
查看当前系统的话题 这里出现的/points_raw
即为激光雷达的数据话题名
rostopic list
然后检查frame_id
的名称是否为velodyne
rostopic echo /points_raw | grep frame_id
那么证明,此处的激光雷达数据 /points_raw
符合建图的要求
分析路线
根据用户线路,进行数据录制
例如本次实例选择在这个场景测试,路线如图
注意:
- 录制前,规划如何行驶录制所需点云数据。
- 分叉路口也多录制一些,回环一下。
- 结束时尽量走到起点前50米处,回环数据。
录制点云数据
前面的启动指令不用关,在CARLA 仿真模拟器
中
按下 B
切换为手动控制
其他操作可以按下 H
查看
将车辆开到目的地后,录制激光雷达的数据,我这里自定义名称为carla_lidar_test.bag
rosbag record -O carla_lidar_test /points_raw
键盘控制车辆移动
当 操控车辆 完成数据的录制后,回到 bag 包的录制终端,按下 < CTRL + C > 停止终端,会默认保存在主目录中
查看 bag 包信息
rosbag info carla_lidar_test.bag
path: carla_lidar_test.bag
version: 2.0
duration: 1:26s (86s)
start: Jan 01 1970 08:01:09.90 (69.90)
end: Jan 01 1970 08:02:36.05 (156.05)
size: 205.7 MB
messages: 1724
compression: none [257/257 chunks]
types: sensor_msgs/PointCloud2 [1158d486dd51d683ce2f1be655c3c181]
topics: /points_raw 1724 msgs : sensor_msgs/PointCloud2
然后关闭所有正在运行的终端进程
创建高精地图
参考网站ubuntu20 autoware+carla联合仿真(一)通过激光雷达制作点云地图_autoware carla-CSDN博客
参数查找
使用 autoware
中的 ndt_mapping
建图模块
首先查询 runtime_manager
在启动 ndt_mapping
中具体是那个功能包和文件
打开文件
/home/heying/autoware.ai/src/autoware/utilities/runtime_manager/scripts/computing.yaml
找到 ndt_mapping
模块的指令,可以看到在 autoware
可视化窗口使用按钮启动是运行了
roslaunch lidar_localizer ndt_mapping.launch
指令
- name : lidar_localizer
desc : lidar_localizer desc sample
subs :
- name : ndt_mapping
desc : ndt_mapping desc sample
cmd : roslaunch lidar_localizer ndt_mapping.launch
param: ndt_mapping
gui :
dialog : MyDialogNDTMapping
dialog_width : 750
dialog_height : 650
incremental_voxel_update:
depend : method_type
depend_bool : 'lambda v : v == 1'
flags : [ nl ]
use_odom:
flags : [ nl ]
imu_topic:
flags : [ nl ]
并且还可以看到 topic
和 msg
的信息 这里是在 launch
启动时需要的建图参数的发布
- name : ndt_mapping
topic : /config/ndt_mapping
msg : ConfigNDTMapping
vars :
- name : resolution
desc : Cell Size while mapping using ND (meters) (default 1.0)
label : Resolution
min : 0.0
max : 10.0
v : 1.0
- name : step_size
desc : Increment value between iterations while matching (default 0.1)
label : Step Size
min : 0.0
max : 1.0
v : 0.1
- name : trans_epsilon
desc : Value to decide convergence between iterations (meters) (default 0.01)
label : Transformation Epsilon
min : 0.0
max : 0.1
v : 0.01
- name : max_iterations
desc : Maximum number of iterations before stopping matching (default 30)
label : Maximum Iterations
min : 1
max : 300
v : 30
- name : leaf_size
desc : Voxel Grid Size of the input scan (downsampling) (default 1.0)
label : Leaf Size
min : 0.0
max : 10.0
v : 1.0
- name : min_scan_range
desc : Ignore points closer than this value (meters) (default 5.0)
label : Minimum Scan Range
min : 0.0
max : 30.0
v : 5.0
- name : max_scan_range
desc : Ignore points far than this value (meters) (default 200.0)
label : Maximum Scan Range
min : 10.0
max : 200.0
v : 200.0
- name : min_add_scan_shift
desc : Minimum distance between points to be added to the final map (default 1.0)
label : Minimum Add Scan Shift
min : 0.0
max : 10.0
v : 1.0
- name : method_type
desc : Method Type
label : Method Type
kind : radio_box
choices:
- pcl_generic
- pcl_anh
- pcl_anh_gpu
- pcl_openmp
descs :
- PCL Generic Implementation
- PCL ANH Implementation
- PCL ANH GPU Implementation
- PCL OpenMP Implementation
v : 0
cmd_param:
dash : ''
delim : ':='
- name : incremental_voxel_update
desc : incremental voxel update
label : Incremental Voxel Update
kind : checkbox
v : False
cmd_param :
dash : ''
delim : ':='
- name : use_odom
desc : Use Odometry to try to reduce errors (read from /odom_pose)
label : Use Odometry
kind : checkbox
v : False
cmd_param :
dash : ''
delim : ':='
- name : use_imu
desc : Use IMU to try to reduce errors
label : Use IMU
kind : checkbox
v : False
cmd_param :
dash : ''
delim : ':='
- name : imu_upside_down
desc : Check if the IMU coordinate system is pointing downwards
label : Inverted IMU
kind : checkbox
v : False
cmd_param :
dash : ''
delim : ':='
- name : imu_topic
desc : IMU raw data source topic
label : imu_topic
v : /imu_raw
kind : topic
topic_type : sensor_msgs/Imu
cmd_param :
dash : ''
delim : ':='
新创建一个功能包 名为map_test
在此功能包中编写launch
文件
ndt_mapping 建图的 launch 编写
那么这个文件用于启动 ndt_mapping
的建图 TF坐标转换 RVIZ可视化
/home/heying/catkin_ws/src/map_test/launch/ndt_mapping.launch
<launch>
<!-- 此文件实现以 launch 的形式完成 ndt_mapping 创建高精地图 -->
<!-- 表示真车雷达中心点与车身后轴中心点的相对位置关系 -->
<param name="/use_sim_time" value="true" />
<param name="tf_x" value="1.2" />
<param name="tf_y" value="0.0" />
<param name="tf_z" value="2.0" />
<param name="tf_yaw" value="0.0" />
<param name="tf_pitch" value="0.0" />
<param name="tf_roll" value="0.0" />
<param name="localizer" value="velodyne" />
<!-- 参数基本选择选择 -->
<arg name="method_type" default="2" /> <!-- pcl_generic=0, pcl_anh=1, pcl_anh_gpu=2, pcl_openmp=3 -->
<arg name="use_odom" default="false" />
<arg name="use_imu" default="false" />
<arg name="imu_upside_down" default="false" />
<arg name="imu_topic" default="/imu_raw" />
<arg name="incremental_voxel_update" default="false" />
<arg name="header" default="auto" />
<arg name="resolution" default="1" /> <!--使用 ND 映射时的像元大小 (米) 默认 1.0 -->
<arg name="step_size" default="0.1" />
<arg name="trans_epsilon" default="0.01" /> <!--用于决定迭代之间的收敛度的值(米) 默认值 0.01 -->
<arg name="max_iterations" default="30" /> <!--停止匹配前的最大迭代次数 默认值为 30 -->
<arg name="leaf_size" default="1" /> <!--体素网格 输入扫描的大小 (缩减采样) 默认值 1.0 -->
<arg name="min_scan_range" default="2.0" /> <!--忽略小于此值的点(米)默认值 5.0 -->
<arg name="max_scan_range" default="200.0" /> <!--忽略大于于此值的点(米)默认值 200.0 -->
<arg name="min_add_scan_shift" default="1.0" />
<!-- 建图参数的发布 -->
<node pkg="rostopic" type="rostopic" name="config_ndt"
args="pub -l /config/ndt_mapping autoware_config_msgs/ConfigNDTMapping
'{ header: $(arg header),
resolution: $(arg resolution),
step_size: $(arg step_size),
trans_epsilon: $(arg trans_epsilon),
max_iterations: $(arg max_iterations),
leaf_size: $(arg leaf_size),
min_scan_range: $(arg min_scan_range),
max_scan_range: $(arg max_scan_range),
min_add_scan_shift: $(arg min_add_scan_shift)
}' "
/>
<!-- 建图运行 -->
<!-- rosrun lidar_localizer ndt_mapping -->
<node pkg="lidar_localizer" type="queue_counter" name="queue_counter" output="screen"/>
<node pkg="lidar_localizer" type="ndt_mapping" name="ndt_mapping" output="screen">
<param name="method_type" value="$(arg method_type)" />
<param name="use_imu" value="$(arg use_imu)" />
<param name="use_odom" value="$(arg use_odom)" />
<param name="imu_upside_down" value="$(arg imu_upside_down)" />
<param name="imu_topic" value="$(arg imu_topic)" />
<param name="incremental_voxel_update" value="$(arg incremental_voxel_update)" />
</node>
<!-- 加载默认world到map的坐标转换 -->
<node pkg="tf" type="static_transform_publisher" name="world_to_map" args="0 0 0 0 0 0 /world /map 10" />
<!-- rviz 可视化 -->
<node pkg="rviz" type="rviz" name="mapping_rviz" args="-d $(find map_test)/rviz/mapping.rviz"/>
<!-- 点云处理 points_preprocessor 的地面滤波 ray_ground_filter 模块 -->
<!-- CARLA 仿真模拟出来的数据已经是经过裁减的 无需使用此模块 -->
<!-- <node pkg="points_preprocessor" type="ray_ground_filter" name="ray_ground_filter" output="screen">
<param name="input_point_topic" value="/points_raw" />
<param name="base_frame" value="base_link" />
<param name="clipping_height" value="1.75" />
<param name="min_point_distance" value="1.85" />
<param name="radial_divider_angle" value="0.08" />
<param name="concentric_divider_distance" value="0.0" />
<param name="local_max_slope" value="8" />
<param name="general_max_slope" value="5.0" />
<param name="min_height_threshold" value="0.07" />
<param name="reclass_distance_threshold" value="0.2" />
<param name="no_ground_point_topic" value="/points_no_ground" />
<param name="ground_point_topic" value="/points_ground" />
</node> -->
</launch>
这里建图的RVIZ
可视化保存配置参数,以下的内容是我设置后的参数,也可以自行定制
/home/heying/catkin_ws/src/map_test/rviz/mapping.rviz
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /PointCloud21
Splitter Ratio: 0.5
Tree Height: 728
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: PointCloud2
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: false
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: false
- Class: rviz/TF
Enabled: true
Filter (blacklist): ""
Filter (whitelist): ""
Frame Timeout: 15
Frames:
All Enabled: true
base_link:
Value: true
map:
Value: true
Marker Scale: 4
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
map:
base_link:
{}
Update Interval: 0
Value: true
- Alpha: 0.5
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Min Color: 0; 0; 0
Name: PointCloud2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.05000000074505806
Style: Flat Squares
Topic: /ndt_map
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: map
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/ThirdPersonFollower
Distance: 21.692182540893555
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.6147972345352173
Target Frame: base_link
Value: ThirdPersonFollower (rviz)
Yaw: 3.1153979301452637
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1025
Hide Left Dock: false
Hide Right Dock: true
QMainWindow State: 000000ff00000000fd00000004000000000000015600000363fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000363000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000363fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000363000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005e10000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: true
Width: 1853
X: 67
Y: 27
PCD 地图的保存 launch
然后编写PCD
地图的保存文件
/home/heying/catkin_ws/src/map_test/launch/map_save.launch
<launch>
<!-- 此文件用于自定义地图的 PCD 保存 -->
<!-- 用于 ndt_mapping.launch 文件 -->
<arg name="header" default="auto" />
<!-- 保存的文件路径与名称 这里需要你自定义-->
<arg name="filename" default="/home/heying/.autoware/test/map/test_map/yuanquan.pcd" />
<!-- 降采样 -->
<arg name="filter_res" default="0.2" />
<node pkg="rostopic" type="rostopic" name="config_map_save" output="screen"
args="pub -l /config/ndt_mapping_output autoware_config_msgs/ConfigNDTMappingOutput
'{ header: $(arg header),
filename: $(arg filename),
filter_res: $(arg filter_res),
}'"
/>
</launch>
启动测试
完成后启动测试
roscore
rosbag play --pause carla_lidar_test.bag
roslaunch map_test ndt_mapping.launch
然后出现了 RVIZ 的格式化窗口
然后回到 rosbag play
的窗口 按下空格键开始播放
可以看到出现了点云地图的数据
ndt_mapping
会根据bag
包回放的 /points_raw
数据
利用激光雷达进行建图 首先需要得到稠密点云
然后进行体素滤波进行过滤得到包含特征的点云数据 接着利用每一帧扫描的点云地图进行ndt配准逐帧拼接 最后能够得到激光雷达扫描路径下的整体点云地图
当bag
包的数据播放完成后
在 ndt_mapping
终端 会输出运行状态的信息
Sequence number: 3088
Number of scan points: 8204 points.
Number of filtered scan points: 1896 points.
transformed_scan_ptr: 8204 points.
map: 2114738 points.
NDT has converged: 1
Fitness score: 4.7753
Number of iteration: 2
(x,y,z,roll,pitch,yaw):
(54.8652, 15.2441, 0.0592597, -0.00121708, -0.000425947, 1.53724)
Transformation Matrix:
0.0335466 -0.999436 -0.00123069 54.903
0.999437 0.0335471 -0.000384878 16.4426
0.000425947 -0.00121708 0.999999 2.05977
0 0 0 1
shift: 0.289804
-----------------------------------------------------------------
(Processed/Input): (1724 / 1724)
然后执行指令 保存地图
roslaunch map_test map_save.launch
可以看到终端输出了以下信息 代表已经保存成功
filter_res: 0.2
filename: /home/heying/.autoware/test/map/test_map/yuanquan_2.pcd
Original: 2114738 points.
Filtered: 271154 points.
(Processed/Input): (1725 / 1724)
Saved 271154 data points to /home/heying/.autoware/test/map/test_map/yuanquan_2.pcd.
可以看到在对应路径中保存成功了 pcd 地图
自此 自定义高精地图的创建与保存的流程结束