Ubuntu20.04部署VINS,并接入PX4作为外部定位信息
部署VINS-Fusion
使用机载电脑为Jetson orin nano,相机为realsense D435,开发环境为Ubuntu20.04、ros-noetic、Ceres 2.0.0,opencv和python为ros-noetic的标准版本。
环境部署可以无脑学习高飞老师的Fast-Drone-250的第7章,很适合新手的无脑环境配置方式。
配置完环境后来到工作空间的/src文件夹,克隆以下两个项目并编译:
git clone https://github.com/IntelRealSense/realsense-ros.git
git clone https://github.com/stevenf7/VINS-Fusion.git
cd ..
catkin_make
realsense-ros是英特尔针对realsense系列相机对ROS做的适配,能够将相机拍摄的图像和信息以ROS话题的形式转发,可以直接订阅使用;
https://github.com/stevenf7/VINS-Fusion.git中的项目是stevenf7修改的适配Ubuntu20.04以及ros-noetic环境的VINS算法,能够直接在该环境下部署并成功编译。
编译成功后进入/VINS-Fusion/config/realsense_D435i文件夹修改对应的配置文件
首先修改VINS-Fusion的定位模式,这里采用imu+双目立体相机,再修改订阅的imu和图像话题,如下图所示
D435i相机有自带的imu,但是该imu的效果不如PX4,因此这里使用了D435的左右眼图像以及PX4的imu数据。
若使用D435i的imu,则可以不修改这两个矩阵。
在图中后面的路径下会输出视觉里程计的轨迹和修正后的外参矩阵
接下来修改外参矩阵,该外参矩阵描述了左右眼相机与imu之间的距离,原文件中使用D435i自带的imu,而我们使用了PX4的imu,所以矩阵需要进行较大的调整
body_T_cam0: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [0, 0, 1, 0.06,
-1, 0, 0, 0.02,
0,-1, 0, -0.11,
0, 0, 0, 1]
body_T_cam1: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [0, 0, 1, 0.06,
-1, 0, 0, -0.03,
0,-1, 0, -0.11,
0, 0, 0, 1]
矩阵的左上角是一个旋转矩阵,描述了相机与imu的旋转关系;矩阵最后一列是相机相对imu的距离,顺序为xyz,x指向PX4飞控前方,右手坐标系。
这只是对外参的初步标定,后续还要进行精确的标定。
修改完VINS的参数后,接着修改相机的参数,确保开启了左右眼相机。
进入/realsense-ros/realsense2_camera/launch文件夹,打开rs_camera.launch文件,将enable_infra1和enable_infra2设置为true,或者可以直接粘贴下面的内容:
<launch>
<arg name="serial_no" default=""/>
<arg name="usb_port_id" default=""/>
<arg name="device_type" default=""/>
<arg name="json_file_path" default=""/>
<arg name="camera" default="camera"/>
<arg name="tf_prefix" default="$(arg camera)"/>
<arg name="external_manager" default="false"/>
<arg name="manager" default="realsense2_camera_manager"/>
<arg name="output" default="screen"/>
<arg name="respawn" default="false"/>
<arg name="fisheye_width" default="640"/>
<arg name="fisheye_height" default="480"/>
<arg name="enable_fisheye" default="false"/>
<arg name="depth_width" default="640"/>
<arg name="depth_height" default="480"/>
<arg name="enable_depth" default="true"/>
<arg name="confidence_width" default="640"/>
<arg name="confidence_height" default="480"/>
<arg name="enable_confidence" default="false"/>
<arg name="confidence_fps" default="30"/>
<arg name="infra_width" default="640"/>
<arg name="infra_height" default="480"/>
<arg name="enable_infra" default="true"/>
<arg name="enable_infra1" default="true"/>
<arg name="enable_infra2" default="true"/>
<arg name="infra_rgb" default="false"/>
<arg name="color_width" default="640"/>
<arg name="color_height" default="480"/>
<arg name="enable_color" default="true"/>
<arg name="fisheye_fps" default="30"/>
<arg name="depth_fps" default="30"/>
<arg name="infra_fps" default="30"/>
<arg name="color_fps" default="30"/>
<arg name="gyro_fps" default="400"/>
<arg name="accel_fps" default="250"/>
<arg name="enable_gyro" default="false"/>
<arg name="enable_accel" default="false"/>
<arg name="enable_pointcloud" default="false"/>
<arg name="pointcloud_texture_stream" default="RS2_STREAM_COLOR"/>
<arg name="pointcloud_texture_index" default="0"/>
<arg name="allow_no_texture_points" default="false"/>
<arg name="ordered_pc" default="false"/>
<arg name="enable_sync" default="false"/>
<arg name="align_depth" default="false"/>
<arg name="publish_tf" default="true"/>
<arg name="tf_publish_rate" default="0"/>
<arg name="filters" default=""/>
<arg name="clip_distance" default="-2"/>
<arg name="linear_accel_cov" default="0.01"/>
<arg name="initial_reset" default="false"/>
<arg name="reconnect_timeout" default="6.0"/>
<arg name="wait_for_device_timeout" default="-1.0"/>
<arg name="unite_imu_method" default=""/>
<arg name="topic_odom_in" default="odom_in"/>
<arg name="calib_odom_file" default=""/>
<arg name="publish_odom_tf" default="true"/>
<arg name="stereo_module/exposure/1" default="7500"/>
<arg name="stereo_module/gain/1" default="16"/>
<arg name="stereo_module/exposure/2" default="1"/>
<arg name="stereo_module/gain/2" default="16"/>
<arg name="emitter_enable" default="false"/>
<group ns="$(arg camera)">
<include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
<arg name="external_manager" value="$(arg external_manager)"/>
<arg name="manager" value="$(arg manager)"/>
<arg name="output" value="$(arg output)"/>
<arg name="respawn" value="$(arg respawn)"/>
<arg name="serial_no" value="$(arg serial_no)"/>
<arg name="usb_port_id" value="$(arg usb_port_id)"/>
<arg name="device_type" value="$(arg device_type)"/>
<arg name="json_file_path" value="$(arg json_file_path)"/>
<arg name="enable_pointcloud" value="$(arg enable_pointcloud)"/>
<arg name="pointcloud_texture_stream" value="$(arg pointcloud_texture_stream)"/>
<arg name="pointcloud_texture_index" value="$(arg pointcloud_texture_index)"/>
<arg name="enable_sync" value="$(arg enable_sync)"/>
<arg name="align_depth" value="$(arg align_depth)"/>
<arg name="fisheye_width" value="$(arg fisheye_width)"/>
<arg name="fisheye_height" value="$(arg fisheye_height)"/>
<arg name="enable_fisheye" value="$(arg enable_fisheye)"/>
<arg name="depth_width" value="$(arg depth_width)"/>
<arg name="depth_height" value="$(arg depth_height)"/>
<arg name="enable_depth" value="$(arg enable_depth)"/>
<arg name="confidence_width" value="$(arg confidence_width)"/>
<arg name="confidence_height" value="$(arg confidence_height)"/>
<arg name="enable_confidence" value="$(arg enable_confidence)"/>
<arg name="confidence_fps" value="$(arg confidence_fps)"/>
<arg name="color_width" value="$(arg color_width)"/>
<arg name="color_height" value="$(arg color_height)"/>
<arg name="enable_color" value="$(arg enable_color)"/>
<arg name="infra_width" value="$(arg infra_width)"/>
<arg name="infra_height" value="$(arg infra_height)"/>
<arg name="enable_infra" value="$(arg enable_infra)"/>
<arg name="enable_infra1" value="$(arg enable_infra1)"/>
<arg name="enable_infra2" value="$(arg enable_infra2)"/>
<arg name="infra_rgb" value="$(arg infra_rgb)"/>
<arg name="fisheye_fps" value="$(arg fisheye_fps)"/>
<arg name="depth_fps" value="$(arg depth_fps)"/>
<arg name="infra_fps" value="$(arg infra_fps)"/>
<arg name="color_fps" value="$(arg color_fps)"/>
<arg name="gyro_fps" value="$(arg gyro_fps)"/>
<arg name="accel_fps" value="$(arg accel_fps)"/>
<arg name="enable_gyro" value="$(arg enable_gyro)"/>
<arg name="enable_accel" value="$(arg enable_accel)"/>
<arg name="publish_tf" value="$(arg publish_tf)"/>
<arg name="tf_publish_rate" value="$(arg tf_publish_rate)"/>
<arg name="filters" value="$(arg filters)"/>
<arg name="clip_distance" value="$(arg clip_distance)"/>
<arg name="linear_accel_cov" value="$(arg linear_accel_cov)"/>
<arg name="initial_reset" value="$(arg initial_reset)"/>
<arg name="reconnect_timeout" value="$(arg reconnect_timeout)"/>
<arg name="wait_for_device_timeout" value="$(arg wait_for_device_timeout)"/>
<arg name="unite_imu_method" value="$(arg unite_imu_method)"/>
<arg name="topic_odom_in" value="$(arg topic_odom_in)"/>
<arg name="calib_odom_file" value="$(arg calib_odom_file)"/>
<arg name="publish_odom_tf" value="$(arg publish_odom_tf)"/>
<arg name="stereo_module/exposure/1" value="$(arg stereo_module/exposure/1)"/>
<arg name="stereo_module/gain/1" value="$(arg stereo_module/gain/1)"/>
<arg name="stereo_module/exposure/2" value="$(arg stereo_module/exposure/2)"/>
<arg name="stereo_module/gain/2" value="$(arg stereo_module/gain/2)"/>
<arg name="allow_no_texture_points" value="$(arg allow_no_texture_points)"/>
<arg name="ordered_pc" value="$(arg ordered_pc)"/>
</include>
</group>
</launch>
修改完成后尝试运行相机和视觉里程计
roslaunch mavros px4.launch //运行mavros负责机载电脑和PX4飞控的通讯,获取PX4的imu数据
roslaunch realsense2_camera rs_camera.launch //启动相机
rosrun vins vins_node ~/UAV_Swarm_Platform/src/VINS-Fusion/config/realsense_d435i/realsense_stereo_imu_config.yaml //运行VINS,工作空间的名字需要根据自己的情况修改
roslaunch vins vins_rviz.launch //运行rviz查看实时轨迹
rostopic echo /vins_estimator/imu_propagate //查看imu预积分得到的位置信息
接着平稳的抱着无人机走动,最后将无人机放回原地,查看定位是否准确。
关闭VINS后,会在前面设置的output_path路径下记录轨迹和自动矫正过的外参,将该外参替换到realsense_stereo_imu_config.yaml中,重复该过程直到定位准确。
过程中如果发现轨迹严重之后,可以将realsense_stereo_imu_config.yaml中的flow_back参数设置为0.开启该功能能够提高vins的定位精度,但是极其影响运算速度,在若使用的机载电脑算力不够,则会造成轨迹滞后。
将VINS定位信息接入PX4
PX4有3个较为常用的模式,分别是自稳模式、位置模式和offboard模式。
自稳模式是最原始的模式,完全依靠遥控器控制飞机飞行,没有定点、定高等功能,因此这个模式不需要定位信息。
位置模式和offboard模式需要外部提供位置信息才能够使用,在没有外部定位信息的情况下,无法切换到这两个模式,因此我们需要将VINS的定位信息接入PX4
mavros就是机载电脑和PX4之间的通信桥梁,启动mavros节点后,该节点能够将PX4的各项数据以ros话题的形式转发,并且会接收指定的ros话题,并将它们以mavlink通讯协议个格式转发给PX4.
前面配置环境时,我们安装了mavros库,但这个库不够全面,缺少了一些消息,我们要补充安转一个mavros-extra库
打开终端,输入以下指令
sudo apt-get install ros-noetic-mavros-extras
接着查看PX4官网https://docs.px4.io/main/zh/ros/external_position_estimation.html
可以看到mavros会接受几种ros话题作为外部定位信息,分别是/mavros/vision_pose/pose、/mavros/odometry/out 、/mavros/mocap/pose.
这里我们选用/mavros/vision_pose/pose,也就是说只要我们在ros中将VINS的定位信息以/mavros/vision_pose/pose话题转发,mavros就会接收到并自动转发给PX4飞控。
接下来就开始编写一个节点,定于VINS估计的位置,并转发出来。
来到工作空间,打开终端,输入以下指令创建功能包
catkin_create_pkg vins_to_mavros std_msgs
在/vins_to_mavros/src文件夹中创建vins_to_mavros.cpp文件,复制如下内容:
#include <ros/ros.h>
#include <geometry_msgs/PoseStamped.h>
#include <nav_msgs/Odometry.h>
ros::Publisher vision_pub;
void vins_callback(const nav_msgs::Odometry::ConstPtr &msg)
{
geometry_msgs::PoseStamped vision_pose;
vision_pose.header.stamp = msg->header.stamp;
// vision_pose.header.frame_id = "map"; // 根据实际情况调整,可能是 "vins_world"
vision_pose.pose = msg->pose.pose;
vision_pub.publish(vision_pose);
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "vins_to_mavros");
ros::NodeHandle nh("~");
//使用/vins_estimator/imu_propagate作为外部定位信息,/vins_estimator/odometry的频率太低,不稳定
ros::Subscriber slam_sub = nh.subscribe<nav_msgs::Odometry>("/vins_estimator/imu_propagate", 100, vins_callback);
vision_pub = nh.advertise<geometry_msgs::PoseStamped>("/mavros/vision_pose/pose", 10);
ros::spin();
return 0;
}
VINS输出的消息中,/vins_estimator/odometry和/vins_estimator/imu_propagate都描述了定位的结果,但是odometry是后端优化过后的结果,因为经过了后端优化后才输出,所以该里程较为滞后,且刷新频率低,用作定位数据不太稳定;而imu_propagate是imu预积分得到的结果,实时性高且频率高,我们选用他作为PX4的外部定位数据。
这部分要注意消息的坐标系,飞控中使用NED坐标系,而vins使用的是以正上方为z轴、正前方为x轴的右手坐标系,mavros在转发消息的时候会自动进行坐标系的转换。
如果vins使用相机imu和相机坐标系,或是接入动捕等其他设备,要先将坐标系变换为与vins相同的右手系再发送给mavros
接下来修改CmakeLists.txt
cmake_minimum_required(VERSION 3.0.2)
project(vins_to_mavros)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
geometry_msgs
mavros_msgs
roscpp
std_msgs
cv_bridge
sensor_msgs
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
find_package(OpenCV REQUIRED)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# geometry_msgs# mavros_msgs# std_msgs
# )
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES offboard_run
# CATKIN_DEPENDS geometry_msgs mavros_msgs roscpp std_msgs
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/offboard_run.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/offboard_run_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_offboard_run.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
add_executable(vins_to_mavros src/vins_to_mavros.cpp)
target_link_libraries(vins_to_mavros ${catkin_LIBRARIES})
修改package.txt文件
<?xml version="1.0"?>
<package format="2">
<name>vins_to_mavros</name>
<version>0.0.0</version>
<description>The vins_to_mavros package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="rui27@todo.todo">rui27</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/offboard_run</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>mavros_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>cv_bridge</build_depend>
<build_depend>image_transport</build_depend>
<build_export_depend>geometry_msgs</build_export_depend>
<build_export_depend>mavros_msgs</build_export_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>mavros_msgs</exec_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>cv_bridge</exec_depend>
<exec_depend>image_transport</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>
修改完成后编译运行
catkin_make
source devel/setup.bash
rosrun vins_to_mavros vins_to_mavros
在终端中查看话题,看是否发布者
rostopic info /mavros/vision_pose/pose
最后打开QGC进行参数的配置
修改参数EKF2_AID_MASK为24,即勾选vision position fusion和vision yaw fusion
修改参数EKF2_HGT_MODE为vision
重启飞控,在Mavlink检测页面查找LOCAL_POSITION_NED,若能找到则说明外部定位消息接入成功。
现在飞机能够成功切换到位置模式或offboard模式。