本页展示了如何使用RPLidarA2激光雷达 设置ROS和谷歌制图师SLAM ,为ArduPilot提供本地位置估计,以便它可以在没有GPS的情况下运行。
这些指令在用APSync 闪存的NVidia TX2 上进行了测试,然后按照此处所述安装了 ROS和MAVROS。
注意
这些页面正在进行中
RPLidar 的方向应使其 USB 电缆线指向与飞行控制器上的箭头相同的方向。
USB 电缆应插入运行 ROS 的配套计算机上的 USB 端口。
将 RPLidarA2 插入配套计算机。如果使用安装在AUVidea J2板上的TX120,请确保激光雷达已插入较低的USB端口。
激光雷达应显示为 /dev/ttyUSB0 或 /dev/ttyACM0。
如果您键入“lsusb”,则设备还应列为“Cygnal Integrated Products, Inc. CP210x UART Bridge / myAVR mySmartUSB 灯”
允许任何人通过输入以下两个命令之一从设备读取,具体取决于上面找到的串行端口
Copy sudo usermod -a -G dialout
Copy sudo apt-get install ros-<distro>-desktop
或者安装这些单独的软件包中的每一个(此列表尚未完成):
Copy sudo apt-get install ros-<distro>-tf ros-<distro>-tf-conversions ros-<distro>-laser-geometry
sudo apt-get install ros-<distro>-cv-bridge ros-<distro>-image-transport
sudo apt-get install qt4-qmake qt4-dev-tools
sudo apt-get install protobuf-compiler
在您的主目录中:
Copy cd $HOME
mkdir -p catkin_ws/src
cd catkin_ws
catkin_init_workspace
在工作区中安装 RPLidar 节点
Copy cd $HOME/catkin_ws/src
git clone https://github.com/Slamtec/rplidar_ros.git
安装更多软件包
Copy sudo apt-get install python-wstool python-rosdep ninja-build
使用 wstool 重新初始化工作区,然后合并 cartographer_ros.rosinstall 文件并获取依赖项的代码。
Copy cd $HOME/catkin_ws
wstool init src
wstool merge -t src https://raw.githubusercontent.com/googlecartographer/cartographer_ros/master/cartographer_ros.rosinstall
wstool update -t src
安装 proto3 和 deb 依赖项
Copy src/cartographer/scripts/install_proto3.sh
sudo rosdep init # if error message appears about file already existing, just ignore and continue
rosdep update
rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y
将机器人姿势发布服务器 包克隆到工作区中
Copy cd $HOME/catkin_ws/src
git clone https://github.com/GT-RAIL/robot_pose_publisher.git
使用您喜欢的编辑器(如“gedit”)创建cartographer_ros启动文件
Copy cd $HOME/catkin_ws/src/cartographer_ros/cartographer_ros/launch
gedit cartographer.launch
将以下内容复制粘贴到文件中
Copy <launch>
<param name="/use_sim_time" value="false" />
<node name="cartographer_node"
pkg="cartographer_ros"
type="cartographer_node"
args="-configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename cartographer.lua"
output="screen">
<remap from="odom" to="/mavros/local_position/odom" />
<remap from="imu" to="/mavros/imu/data" />
</node>
<node name="cartographer_occupancy_grid_node"
pkg="cartographer_ros"
type="cartographer_occupancy_grid_node" />
<node name="robot_pose_publisher"
pkg="robot_pose_publisher"
type="robot_pose_publisher"
respawn="false"
output="screen" >
<param name="is_stamped" type="bool" value="true"/>
<remap from="robot_pose" to="/mavros/vision_pose/pose" />
</node>
<node pkg="tf" type="static_transform_publisher" name="base_to_laser_broadcaster" args="0 0 0 0 0 0 base_link laser 100" />
</launch>
使用我们最喜欢的编辑器(如“gedit”)创建制图师.lua脚本
Copy cd $HOME/catkin_ws/src/cartographer_ros/cartographer_ros/configuration_files
gedit cartographer.lua
将以下内容复制粘贴到文件中
Copy 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 = "base_link",
odom_frame = "odom",
provide_odom_frame = true,
publish_frame_projected_to_2d = false,
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.min_range = 0.05
TRAJECTORY_BUILDER_2D.max_range = 30
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 8.5
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 0.2
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 5
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 = 1.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 10
TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.2)
-- for current lidar only 1 is good value
TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 1
TRAJECTORY_BUILDER_2D.min_z = -0.5
TRAJECTORY_BUILDER_2D.max_z = 0.5
POSE_GRAPH.constraint_builder.min_score = 0.65
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.65
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 30
return options
注意
无需手动修改上述包,而是克隆此 存储库并安装依赖项。
Copy cd $HOME/catkin_ws
catkin build
source devel/setup.bash
将RPLidarA2插入配套计算机,然后打开四个终端,每种终端类型:
Copy cd catkin_ws
source devel/setup.bash
然后在 1 号航站楼:
在 2 号航站楼:
Copy roslaunch rplidar_ros rplidar.launch
在 3 号航站楼:
Copy roslaunch cartographer_ros cartographer.launch
在 4 号航站楼:
按照与 ROS 连接页面上 的说明启动 mavros,其中涉及运行如下命令:
Copy roslaunch mavros apm.launch fcu_url:=udp://:14855@
使用地面站(即任务规划器)连接到飞行控制器,并检查是否设置了如下所示的参数:
更改上述任何值后,重新启动飞行控制器。
如果一切正常,视觉位置估计应该开始从ROS流入ArduPilot。这可以通过使用任务规划器(或类似工具)连接到飞行控制器并检查飞行数据屏幕的消息选项卡(左下角)来确认来自 EKF 的消息,如下所示:
Copy EKF2 IMU1 initial pos NED = 0.0,0.0,0.0 (m)
EKF2 IMU1 is using external nav data
EKF2 IMU0 initial pos NED = 0.0,0.0,0.0 (m)
EKF2 IMU0 is using external nav data
使用任务规划器(或类似工具)转到“飞行数据”屏幕,右键单击地图,然后选择“在此处设置主页”>>“设置EKF原点”。车辆应立即出现在您单击的地图上。
要确认ROS端工作正常,请键入以下命令,并显示制图师的位置估计的实时更新
Copy rostopic echo /robot_pose
Mission Planner的MAVLink检查器(按Ctrl-F,然后按“MAVLink检查器”按钮)可用于检查VISION_POSITION_ESTIMATE消息是否成功发送到飞行控制器
注意
我们热衷于改进ArduPilot对ROS的支持,因此如果您发现问题(例如似乎不支持的命令),请在ArduPilot问题列表中 报告它们,标题包含“ROS”,我们将尝试尽快解决这些问题。