1 故事的开端
故事还得从几天前说起,在浏览网页时,偶然间发现了husky机器人,发现真的是泰库辣!因此,就想着要是能利用这个模型作为实验平台该有多好(虽然,在此之前,本文也搭建了一个基于平面模型的复合移动机器人,但是还是没能抵住husky的诱惑),于是就开始有了这一篇博文。
2 husky模型
非常幸运的是目前在ros已经支持husky,husky也有自己很多集成的功能包,因此想要利用husky实在是太方便了,完全不用重复造轮子。先看看husky帅气的造型。
3 husky的获取
husky的制作团队非常人性化,可以根据自己的需求自定义husky的模型,要想使用husky可以通过下面的链接GitHub - husky/husky: Common packages for the Clearpath Husky
将项目克隆到自己的系统,然后进入到src/husky/husky_description/urdf/ghm_husky.urdf.xacro文件中,想要使用哪个传感器就将其enable值设为1。为了能够使用husky,需要安装官方配置的功能包,直接调用命令:sudo apt-get install ros-noetic-husky-*,注意noetic是你安装的对应的ros版本.
由于本人目前只研究2D激光slam,因此只添加了支架和一个单线雷达就非常足够了。下面是我的husky模型图
顺便提一下目前husky可支持很多传感器,例如在单线雷达中有LMS1XX Laser和UST10 Laser。多线激光雷达有Velodyne LiDAR ,相机模型有Realsense Camera和 BlackflyS Camera ,才外还配有OutdoorNav。并且自身配备了IMU和里程计,因此,无论是激光SLAM还是视觉SLAM,又或者是多传感器融合的SLAM研究者来说,这都是一个很大的福音。
4 仿真环境
仿真环境可以通过gazebo中的srf模型进行搭建,gazebo自带的模型比较少,可以通过mirrors / osrf / gazebo_models · GitCode
将官方支持的模型下载下来为已所用。目前本人正处于研究阶段,所以仿真环境暂时不能展示,对管gezebo仿真环境的搭建可以找一下博文卡学习。
5 建图测试
首先运行husky的描述文件和仿真环境,并且运行cartographer的节点,此时可以看到类似的节点订阅情况:
然后tf树大致如下
通过查看发布的topic 可以看到husky有控制速度的话题,因此我这里为了方便直接使用rqt_robot_steer节点对其进行控制。当运动小车在仿真环境中走完一圈,建图基本上完成了,建好的地图如下
可以看到建好的地图还是很光滑的,轮廓也比较明显,不过还有部分地方没有扫描到,可能是激光雷达的范围设置小了,后面可以调整参数优化一下。
附 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.
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "base_link",--[[ 将所有传感器数据转换到这个坐标系下,如果有imu,
一般设置为imu_link,因为imu的频率非常高(上百hz),而雷达数据的频率相对低(几十hz),
如果把imu数据转换到其他坐标系则每秒钟需要转换几百次,比较耗费资源 ]]
published_frame = "odom", --[[ 设置为tf树最顶端的坐标系名称,设置完成后cartographer会发布map->published_frame的坐标系 ]]
odom_frame = "odom",
provide_odom_frame = false, --[[ 是否提供odom的tf, 如果为true,则tf树为map->odom->footprint,如果为false,则tf树为map->published_frame ]]
publish_frame_projected_to_2d = false, --[[ 如果启用,发布的姿势将被限制为纯 2D 姿势(无滚动、俯仰或 z 偏移)。
这可以防止在 2D 模式下由于姿势外推步骤而可能发生的潜在不需要的平面外姿势(例如,如果姿势应发布为类似“基本足迹”的帧) ]]
use_pose_extrapolator = true,
use_odometry = false, --[[ 如果启用,则订阅主题为“odom”的nav_msgs/Odometry 。在这种情况下必须提供里程表,该信息将包含在 SLAM 中。 ]]
use_nav_sat = false,
use_landmarks = false, --[[ 如果启用,则订阅主题为“修复”的sensor_msgs/NavSatFix 。这种情况下必须提供导航数据,该信息将包含在全局 SLAM 中。 ]]
num_laser_scans = 1, --[[ 要订阅的激光扫描主题数。为一台激光扫描仪订阅 sensor_msgs/LaserScan的“扫描”主题,
或为多台激光扫描仪订阅主题“scan_1”、“scan_2”等。 ]]
num_multi_echo_laser_scans = 0, --[[ 要订阅的多回波激光扫描主题的数量。
为一台激光扫描仪订阅“回声”主题的sensor_msgs /MultiEchoLaserScan ,
或为多台激光扫描仪订阅“echoes_1”、“echoes_2”等主题。 ]]
num_subdivisions_per_laser_scan = 1, --[[ 将每个接收到的(多回波)激光扫描分成的点云数。
细分扫描可以使扫描仪移动时获取的扫描不变形。有一个相应的轨迹生成器选项,可以将细分的扫描累积到一个点云中,用于扫描匹配 ]]
num_point_clouds = 0, --[[ 要订阅的点云主题数。为一个测距仪订阅 “points2”主题上的sensor_msgs/PointCloud2 ,
或为多个测距仪订阅主题“points2_1”、“points2_2”等。 ]]
lookup_transform_timeout_sec = 0.2, --[[ 用于使用tf2查找转换的超时秒数。 ]]
submap_publish_period_sec = 0.3, --[[ 发布子图姿势的时间间隔(以秒为单位),例如 0.3 秒。 ]]
pose_publish_period_sec = 5e-3, --[[ 发布姿势的时间间隔(以秒为单位),例如 5e-3 表示频率为 200 Hz。 ]]
trajectory_publish_period_sec = 30e-3, --[[ 发布轨迹标记的时间间隔(以秒为单位),例如 30e-3 30 毫秒。 ]]
rangefinder_sampling_ratio = 1., --[[ 测距仪消息的固定比率采样。 ]]
odometry_sampling_ratio = 1., --[[ 里程计消息的固定比率采样。 ]]
fixed_frame_pose_sampling_ratio = 1., --[[ GPS消息的固定比率采样。 ]]
imu_sampling_ratio = 1., --[[ IMU 消息的固定比率采样。 ]]
landmarks_sampling_ratio = 1., --[[ 地标消息的固定比率采样。 ]]
}
MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.use_imu_data = true
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 100.
TRAJECTORY_BUILDER_2D.min_z = 0.2
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = false
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 1.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 1.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 1.
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 80.
TRAJECTORY_BUILDER_2D.submaps.grid_options_2d.resolution = 0.1
POSE_GRAPH.optimize_every_n_nodes = 160.
POSE_GRAPH.constraint_builder.sampling_ratio = 0.3
POSE_GRAPH.constraint_builder.max_constraint_distance = 15.
POSE_GRAPH.constraint_builder.min_score = 0.48
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.60
return options
参考链接:
https://github.com/husky/husky
https://github.com/xiangli0608/cartographer_detailed_comments_ws
cartographer lua参数解析_cartographer lua文件_NOA_GG的博客-优快云博客
下一篇预告:将ur5机械臂添加到husky中,搭建复合移动机器人。