?上一篇文章講了cartographer算法手持雷達(dá)建圖的參數(shù)調(diào)試,這篇進(jìn)一步講如何融合2D雷達(dá)與IMU采用cartographer算法進(jìn)行slam建圖。
cartographer算法手持二維激光雷達(dá)建圖(不使用里程計(jì)及IMU)
https://blog.csdn.net/wangchuchua/article/details/127268037?spm=1001.2014.3001.5502
首先先說一下我的硬件設(shè)備:
思嵐s1激光雷達(dá)、Tobotics ROS IMU HFI-A9。
??和上一篇講的一樣在進(jìn)行文件修改之前一定一定要先弄明白自己的雷達(dá)和IMU的話題名稱topic_id以及frame_id,否則名稱對(duì)不上肯定是會(huì)報(bào)錯(cuò)的。
首先啟動(dòng)雷達(dá),如果有用思嵐激光雷達(dá)的小伙伴可以參考這個(gè)網(wǎng)址。(只要可以實(shí)現(xiàn)點(diǎn)云信息的發(fā)布就好。)ROS與激光雷達(dá)入門教程-ROS中使用激光雷達(dá)(思嵐S1) - 創(chuàng)客智造
雷達(dá)的frame_id就是圖中畫紅圈的,我的是laser。
??接下來就是查看雷達(dá)的話題名稱,打開終端輸入:
rostopic list
可以看到雷達(dá)topic名稱一般都是scan。同時(shí)還有另一種方法查詢雷達(dá)的frame_id,就是在終端輸入:
rostopic echo /topic | grep frame_id
其中topic名稱輸入你雷達(dá)的話題名稱就可,我的話題名稱是scan所以輸入:
rostopic echo /scan | grep frame_id
?這樣就能查到話題scan的fram_id啦。通過以上操作我得知了我的雷達(dá)話題是scan、frame_id是laser。
?好接下來啟動(dòng)IMU模塊,一般rosIMU是會(huì)有啟動(dòng)包的,啟動(dòng)IMU后通過rostopic查詢一下IMU的話題名稱,我的話題名稱是/imu。知道話題名稱后輸入命令:rostopic echo /imu?| grep frame_id查詢frame-id。通過以上操作我得知了我IMU的話題名稱是/imu,frame-id是base_link。知道這些后就開始正式的修改相關(guān)的文件。
首先找到~/google_ws/src/cartographer_ros/cartographer_ros/configuration_files目錄下的建立一個(gè)revo_lds.lua文件,為了和手持建圖的lua文件區(qū)分開,我有復(fù)制了這個(gè)文件,重命名為revo_imu.lua。修改后文件內(nèi)容如下:
-- 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.
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "base_link",
published_frame = "laser",
odom_frame = "odom",
provide_odom_frame = true,
publish_frame_projected_to_2d = false,
use_pose_extrapolator = true,
use_odometry = false,
use_nav_sat = false,
use_landmarks = false,
num_laser_scans = 1,
num_multi_echo_laser_scans = 0,
num_subdivisions_per_laser_scan = 1,
num_point_clouds = 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.submaps.num_range_data = 35
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 8.
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1.
TRAJECTORY_BUILDER_2D.use_imu_data = true
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
POSE_GRAPH.constraint_builder.min_score = 0.65
return options
主要修改的點(diǎn)就是一下三個(gè)地方:
tracking_frame = "base_link",#這里要與imu的frame_id名稱一致
published_frame = "laser",#這里要與雷達(dá)的frame_id名稱一致
TRAJECTORY_BUILDER_2D.use_imu_data = true
然后在~/google_ws/src/cartographer_ros/cartographer_ros//urdf/文件下創(chuàng)建一個(gè)urdf文件文件內(nèi)容如下所示(我的urdf文件名稱是:backpack_2d1.urdf,原本包里自帶了兩個(gè)urdf文件因?yàn)槲乙约赫{(diào)整imu和雷達(dá)的位置關(guān)系就另寫了一個(gè)urdf文件):這里一定要注意urdf里的link name一定要與雷達(dá)或者imu的fram_id相對(duì)應(yīng)。
<!--
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="base_link">#與imu的fram_id對(duì)應(yīng)
<visual>
<origin xyz="0 0 0" />
<geometry>
<box size="0.06 0.04 0.02" />
</geometry>
<material name="orange" />
</visual>
</link>
<link name="laser">#與雷達(dá)的fram_id對(duì)應(yīng)
<visual>
<origin xyz="0 0 0" />
<geometry>
<cylinder length="0.05" radius="0.03" />
</geometry>
<material name="gray" />
</visual>
</link>
<joint name="imu2laser" type="fixed">
<parent link="laser" />
<child link="base_link" />
<origin xyz="0 0 -0.035" />
</joint>
</robot>
?在riviz中顯示是這樣的,小老板們可以根據(jù)需要調(diào)整雷達(dá)和imu之間的相對(duì)位置關(guān)系。
在~/google_ws/src/cartographer_ros/cartographer_ros/launch目錄下建立launch文件,我的文件名稱是demo_revo_sc_imu.launch。文件內(nèi)容如下:
<!--
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.
-->
<launch>
<param name="/use_sim_time" value="false" />
<node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
<param name="serial_port" type="string" value="/dev/ttyUSB0"/>
<param name="serial_baudrate" type="int" value="256000"/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
</node>
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename revo_imu.lua"
output="screen">
<remap from="scan" to="scan" />
<remap from="imu/data" to="imu" />#這里是你的imu的話題名稱
</node>
<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
<param name="robot_description" textfile="$(find cartographer_ros)/urdf/backpack_2d1.urdf" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" required="true"
args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
</launch>
這個(gè)文件中包含了啟動(dòng)雷達(dá)節(jié)點(diǎn),和cartographer建圖節(jié)點(diǎn),相對(duì)于上節(jié)的launch文件內(nèi)容增加了?
?<remap from="imu/data" to="imu" />注意要用你自己imu的話題名稱。
以及 urdf文件,注意要對(duì)應(yīng)你的urdf文件路徑。
<param name="robot_description" textfile="$(find cartographer_ros)/urdf/backpack_2d1.urdf" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
到這里文件調(diào)整部分就完成了,可以開始啟動(dòng)建圖了,因?yàn)樯厦娴膌aunch文件沒有包含imu啟動(dòng)節(jié)點(diǎn)所以我這里先單獨(dú)啟動(dòng)imu。?
roslaunch handsfree_ros_imu imu1.launch
imu啟動(dòng)之后就可以運(yùn)行?demo_revo_sc_imu.launch文件了,別忘記啟動(dòng)之前要catkin_make_isolated --install --use-ninja。
source install_isolated/setup.bash
catkin_make_isolated --install --use-ninja
roslaunch cartographer_ros demo_revo_sc_imu.launch
?運(yùn)行成功后的效果是這樣的。
?打開終端輸入rqt_graph查看節(jié)點(diǎn)關(guān)系,我們可以看到imu和雷達(dá)信息已經(jīng)輸入到cartographer的節(jié)點(diǎn)中去說明融合成功了。
rqt_graph
打開終端輸入rosrun rqt_tf_tree rqt_tf_tree得到tf關(guān)系圖:?
文章來源:http://www.zghlxwxcb.cn/news/detail-409304.html
到這里就完成了cartographer算法的雷達(dá)與IMU融合建圖。希望這篇文章能夠幫助到大家,祝大家生活愉快,學(xué)業(yè)順利 (*^▽^*)。文章來源地址http://www.zghlxwxcb.cn/news/detail-409304.html
到了這里,關(guān)于Cartographer算法2D激光雷達(dá)與IMU融合建圖 首先先說一下我的硬件設(shè)備:的文章就介紹完了。如果您還想了解更多內(nèi)容,請(qǐng)?jiān)谟疑辖撬阉鱐OY模板網(wǎng)以前的文章或繼續(xù)瀏覽下面的相關(guān)文章,希望大家以后多多支持TOY模板網(wǎng)!