(猫崽子生病了,这一段时间忙着给它看病,花了好多钞票了!哎!)
相信大家装cartographer都可以跑通官网上的示例教程,所以,博主就在这里写一些跑自己数据包的经验,一呢,作为记录,预防自己老年健忘,二呢,跟大家分享一下经验。
如标题所示,博主用的是激光雷达数据和IMU数据进行建图。
硬件:北科天绘16线机械激光雷达,水平视角360度,10hz/s.惯导:诺瓦泰惯导系统,这个应该是全世界最好的惯导系统了吧.(如果不是,才疏学浅,孤陋寡闻,请见谅)
软件:Ubuntu1604,ROS-Kinetic,cartographer框架
(建议:改动文件建议自己复制源文件进行新建文件改动,源文件作为保留用。)
废话不多说,开始吧!
<!--
Copyright 2016 The Cartographer Authors
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
-->
<robot name="mini">
<material name="orange">
<color rgba="1.0 0.5 0.2 1" />
</material>
<material name="gray">
<color rgba="0.2 0.2 0.2 1" />
</material>
<link name="imu">
<visual>
<origin xyz="0 0 0" />
<geometry>
<box size="0.06 0.04 0.02" />
</geometry>
<material name="orange" />
</visual>
</link>
<link name="lidar_mid">
<visual>
<origin xyz="0 0 0" />
<geometry>
<cylinder length="0.05" radius="0.03" />
</geometry>
<material name="gray" />
</visual>
</link>
<joint name="imu2lidar" type="fixed">
<parent link="lidar_mid" />
<child link="imu" />
<origin xyz="0 0 0" />
</joint>
</robot>
这里稍作解释:里面首先定义了两个坐标系,一个imu 的,一个雷达的,变换关系是通过joint关节信息进行添加,要根据你们自己实际情况进行添加,博主太懒,所以,变换参数懒得去填写了,依然是跑的通的.
里面是我通过3d点云转过来的数据.
~/catkin_cartographer/src/cartographer_ros/cartographer_ros/
这两个文件夹里最主要的东西都是一样的,configuration_files是存储.lua的文件夹,launch是存储启动命令的文件夹,urdf是存储小车模型的文件夹.
**注意:**配置文件夹里的urdf决定了你的小车的模型,即TF树,源文件夹里的urdf你可以不用管.
而urdf文件在上面有说过了.
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "imu", #这里用到了imu,所以跟踪的是imu,如果只用雷达,把这个写lidar_mid
published_frame = "lidar_mid",
odom_frame = "odom",
provide_odom_frame = false,#我不用里程计
publish_frame_projected_to_2d = false,
use_pose_extrapolator = false,
use_odometry = false,
use_nav_sat = false,#不用GPS
use_landmarks = false,
num_laser_scans = 1,#雷达个数
num_multi_echo_laser_scans = 0,
num_subdivisions_per_laser_scan = 1,#这个参数必须要填,>=1,博主目前也没搞明白.
num_point_clouds = 0,#3d的话这里要改,2d填0
lookup_transform_timeout_sec = 0.2,
submap_publish_period_sec = 0.3,
pose_publish_period_sec = 5e-3,
trajectory_publish_period_sec = 30e-3,
rangefinder_sampling_ratio = 1.,
odometry_sampling_ratio = 1.,
fixed_frame_pose_sampling_ratio = 1.,
imu_sampling_ratio = 1.,
landmarks_sampling_ratio = 1.,
}
MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 1
return options
保存退出,进入同级目录的launch文件夹下,新建demo_my_robot.launch文件(可复制backpack_2d.launch,然后修改),内容如下
<launch>
<param name="robot_description"
textfile="$(find cartographer_ros)/urdf/minibus.urdf" />#这里是你第一步定义的urdf文件
<node name="robot_state_publisher" pkg="robot_state_publisher"
type="robot_state_publisher" />
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename my_robot.lua"#这里是你刚才新建的lua文件
output="screen">
<remap from="scan" to="/scan" />#这里是我的2d包里雷达话题/Scan到carto框架Scan的映射
<remap from="imu" to="/imu" />
</node>
<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
</launch>
注意:用的时候要删除我的汉字注释,xml文件的注释方式不是#,博主只是懒的打那些符号了.
然后,在该文件夹里找到demo_backpack_2d.launch文件,用gedit打开修改成:
<launch>
<param name="/use_sim_time" value="true" />
<include file="$(find cartographer_ros)/launch/demo_my_robot.launch" />#这里是你刚才建立的launch文件
<node name="rviz" pkg="rviz" type="rviz" required="true"
args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
<node name="playbag" pkg="rosbag" type="play"
args="--clock $(arg bag_filename)" />
</launch>
保存退出到同级目录中,进入urdf文件夹,检查minibus.urdf文件是否存在,且里面坐标变换关系是否正确.至此,配置文件夹里的改动结束.
5.第五步, 配置源文件夹里的文件.
步骤按照配置文件夹里的配置步骤来,懒的话,直接复制过去也是可以的.
6.第六步, 检查两个文件夹里做了相同的配置之后,保存退出到工作空间路径:
cd ~
cd ~/catkin_cartographer/
catkin_make_isolated --install --use-ninja
source devel_isolated/setup.bash
cd ~
cd ~/catkin_cartographer/
source devel_isolated/setup.bash
roslaunch cartographer_ros demo_backpack_2d.launch bag_filename:=~/2d.bag
不出意外你将会看到这个(csdn好像不能插动图,反正允许插入动图博主也不会,才疏学浅,孤陋寡闻,各位请见谅!)
cd catkin_cartographer/
source devel_isolated/setup.bash
rosservice call /finish_trajectory 0
rosservice call /write_state "{filename: '${HOME}/Downloads/mymap.pbstream'}"
至此,完工,建好的图也被保存在了Home/Download/路径下,名字为mymap.pbstream。
建图过程中,默认开了全局的闭环,所以你能清晰看到路径修正.效果很棒,个人感觉,不要太棒了!不过,后面测试定位的 时候发现,室内2d建图加纯定位模式成功了,但在室外,纯定位用不了.下一篇,想出一篇配置参数的含义的文章.
(博主今天刚刚实车测试了3d,效果更棒,不管是室内室外都不影响,而且室外定位相当稳,哈哈哈哈,这个后面我会再出一篇来讲的.)