PX4 Ardupilot MAVSDK
该文档介绍了PX4和Ardupilot的MAVSDK及MAVROS开发手册,包括通信流程、节点、连接方式、插件、飞行模式、飞行控制功能、飞行数据获取和常用消息类型等内容。详细列出了各类消息的名称、类型和常用成员变量,并提供了相关链接以供参考。
type
status
date
slug
summary
tags
category
icon
password
SDK框架
- MAVSDK Introduction:
- MAVROS Introduction:
MAVSDK开发手册
For C++ Programming
- MAVSDK C++ QuickStart:
- MAVSDK APIs Guide:
- C++ Examples:
- MAVSDK Server Plugins:
- (Important) MAVSDK API Reference:
Communication Flowchart

Examples
This section contains examples showing how to use MAVSDK.
Example | Description |
Simple example to demonstrate how to imitate a smart battery. | |
Simple example showing how to initiate calibration of gyro, accelerometer, magnetometer. | |
Shows how to create, upload, and run missions. | |
Example to connect multiple vehicles and make them follow their own separate plan file. Also saves the telemetry information to CSV files. | |
Demonstrates how to put vehicle in Follow Me Mode and set the current target position and relative position of the drone. | |
Demonstrates how to define and upload a simple polygonal inclusion GeoFence. | |
Creates and starts an interactive shell session. | |
Demonstrates how to create/use a MAVLink FTP client. | |
Demonstrates how to start/set up a MAVLink FTP server. | |
Example to connect multiple vehicles and make them take off and land in parallel. | |
Demonstrates how to control a vehicle in Offboard mode using velocity commands (in both the NED and body frames). | |
Shows basic usage of the SDK (connect to port, detect system (vehicle), arm, takeoff, land, get telemetry) | |
Shows how to transition a VTOL vehicle between copter and fixed-wing modes. | |
Shows how to construct and play a tune. |
Telemetry API Overview
The
Telemetry
API provides methods to return the following types of information:- Battery - voltage and percentage power remaining.
- EulerAngle - vehicle attitude/orientation as Euler Angle
- GpsInfo - type of fix, if any, and number of satellites.
- Health - calibration status of various sensors and confirmation that position estimates are good enough for position control.
- Position - latitude and longitude in degrees, and altitude relative to sea level and to the takeoff altitude.
- Quaternion - vehicle attitude/orientation as a quaternion
- RcStatus - connection status, signal strength, and whether RC has ever been connected.
MAVROS开发手册
For C++ Programming
- MAVROS C++ Quickstart:
- MAVROS常用消息类型表:
Communication Flowchart

Description
- Nodes:
- mavros_node: main communication node.
- gsc_bridge: Additional proxy. Old name ros_udp.
- event_launcher: Listens to arming status, triggers and run programs on event. Example config.
- Connection: Connection defined by URL, you can use any supported type for FCU and GCS.
- Protocol: Serial/ Serial with hardware flow control/ UDP/ UDP Broadcast/ TCP client/ TCP server
- Plugins: Standard set of communication plugins loaded by mavros_node.
- 3dr_radio: Publish 3DR Radio status to diagnostics and topic.
- actuator_control: Sends acruator commands to FCU.
- hil_control: Publish HIL_CONTROLS.
- command: Send COMMAND_LONG to FCU.
- ftp: Support plugin for MAVLink-FTP ( PX4 ).
- global_position: Publish global position information fused by FCU and raw GPS data.
- imu_pub: Publish IMU state
- local_position: Publish LOCAL_POSITION_NED in TF and PoseStamped topic.
- manual_control: Publish MANUAL_CONTROL message (user input).
- param: Allows to access to FCU parameters and map it to ROS parameters in ~param/.
- rc_io: Publish RC receiver inputs.
- safety_area: Sends safety allowed area to FCU. Initial area can be loaded from parameters.
- setpoint_accel: Send acceleration setpoint.
- setpoint_position: Sends position setpoint using SET_POSITION_TARGET_GLOBAL_INT or SET_POSITION_TARGET_LOCAL_NED.
- setpoint_raw: Send RAW setpoint messages to FCU and provide loopback topics (PX4).
- setpoint_velocity: Send velocity setpoint to FCU.
- sys_status: System status plugin. Handles FCU detection. REQUIRED never blacklist it!.
- sys_time: System time plugin. Does time syncronization on PX4 .
- vfr_hud: Publish VFR_HUD and WIND messages.
- waypoint: Allows to access to FCU mission (waypoints).
Control Mode
- 基础飞行动作/ 飞行模式
上锁/ 锁定/ 起飞和降落/ 返航等
arming Services 加解锁服务
模式切换
PX4支持的模式有:
MODE | MANUAL | ACRO | ALTCTL | POSCTL | OFFBOARD | STABILIZED | RATTITUDE | AUTO.MISSION | AUTO.LOITER | AUTO.RTL | AUTO.LAND | AUTO.READY | AUTO.TAKEOFF | AUTO.FOLLOW_TARGET | AUTO.PRECLAND |
飞行模式 | 手动 | 特技 | 定高 | 定点 | 外部控制 | 自稳 | 姿态特技 | 自动任务 | 自动留待 | 自动返航 | 自动降落 | 自动模式就绪 | 自动起飞 | 自动跟踪目标 | 精准着陆 |
是否需要定点信息 | N | N | N | Y | Y | N | N | Y | Y | Y | Y | Y | Y | Y | Y |
支持的飞控类型 | <br /> | ㅤ | ㅤ | ㅤ | ㅤ | ㅤ | ㅤ | ㅤ | ㅤ | ㅤ | ㅤ | ㅤ | ㅤ | ㅤ | ㅤ |
Ardupilot支持的模式有:
Mode | Alt Ctrl | Pos Ctrl | Pos Sensor | Summary |
Acro | - | - | ㅤ | Holds attitude, no self-level |
Airmode | - | -/+ | ㅤ | Actually not a mode, but a feature,see below |
Alt Hold | s | + | ㅤ | Holds altitude and self-levels the roll & pitch |
Auto | A | A | Y | Executes pre-defined mission |
AutoTune | s | A | Y | Automated pitch and bank procedure to improve control loops |
Brake | A | A | Y | Brings copter to an immediate stop |
Circle | s | A | Y | Automatically circles a point in front of the vehicle |
Drift | - | + | Y | Like stabilize, but coordinates yaw with roll like a plane |
Flip | A | A | ㅤ | Rises and completes an automated flip |
FlowHold | s | A | ㅤ | Position control using Optical Flow |
Follow | s | A | Y | Follows another vehicle |
Guided | A | A | Y | Navigates to single points commanded by GCS |
Heli_Autorotate | A | A | Y | Used for emergencies in traditional helicopters. Helicopter only. Currently SITL only. |
Land | A | s | (Y) | Reduces altitude to ground level, attempts to go straight down |
Loiter | s | s | Y | Holds altitude and position, uses GPS for movements |
PosHold | s | + | Y | Like loiter, but manual roll and pitch when sticks not centered |
RTL | A | A | Y | Returns above takeoff location, may also include landing |
Simple/Super Simple | ㅤ | ㅤ | Y | An add-on to flight modes to use pilot's view instead of yaw orientation |
SmartRTL | A | A | Y | RTL, but traces path to get home |
Sport | s | s | ㅤ | Alt-hold, but holds pitch & roll when sticks centered |
Stabilize | - | + | ㅤ | Self-levels the roll and pitch axis |
SysID | - | + | ㅤ | Special diagnostic/modeling mode |
Throw | A | A | Y | Holds position after a throwing takeoff |
Turtle | - | - | ㅤ | Allows reversing and spinning up adjacent pairs of motors in order to flip a crashed, inverted vehicle back upright |
ZigZag | A | A | Y | Useful for crop spraying |
Symbol | Definition |
- | Manual control |
+ | Manual control with limits & self-level |
s | Pilot controls climb rate |
A | Automatic control |
- 参考坐标系
FRD机体坐标系:X Forward, Y Right, Z Down
NED坐标系:X North, Y East, Z Down
FLU机体坐标系:X Forward, Y Left, Z Up
The local/world and world frames used by ROS and PX4 are different.
Frame | PX4 | ROS |
Body | FRD (X Forward, Y Right, Z Down) | FLU (X Forward, Y Left, Z Up), usually named base_link |
World | FRD or NED (X North, Y East, Z Down) | FLU or ENU (X East, Y North, Z Up), with the naming being odom or map |
- 飞行控制功能
(全局/ 本地)位置控制/ 速度控制
actuator_control 控制飞控IO输出(mixing_and_actuators 混控器)
setpoint_accel 控制期望的加速度
setpoint_attitude 控制期望的姿态
setpoint_position 控制期望的位置(相对坐标或GPS坐标)
setpoint_velocity 控制期望的速度
- 飞行数据获取
global_position 订阅GPS数据
imu_pub 订阅IMU信息
local_position 订阅本地位置数据
manual_control 订阅遥控器的值
sys_status 查询系统状态
waypoint 航点信息
- 定位数据来源
通过修改EKF2位置融合数据获取来源来实现(EKF2_AID_MASK)
视觉数据融合有以下几种方式:
vision position fusion 使用视觉定位数据融合
vision velocity fusion 使用视觉速度数据融合
vision yaw fusion 使用视觉偏航数据融合
external vision rotation 使用外部视觉的旋转数据代替
- 高度数据获取
通过修改EKF2高度融合数据获取来源来实现(EKF2_HGT_REF)
barometer 气压计高度
GNSS GPS高度
range sensor 测距传感器高度
vision 视觉高度
mavros常用消息类型表
mavros订阅消息:
- global_position 订阅GPS数据
消息名称:
mavros/global_position/global
类型名称:
sensor_msgs::NavSatFix.h
类型所在头文件:
sensor_msgs/NavSatFix.h
常用类成员变量:
- imu_pub 订阅IMU信息
消息名称:滤波后的
mavros/imu/data
(或原始信息 mavros/imu/data_raw
)类型名称:
sensor_msgs::Imu
类型所在头文件:
sensor_msgs/Imu.h
常用类成员变量:
- local_position 订阅本地位置数据
消息名称:
mavros/local_position/pose
类型名称:
geometry_msgs::PoseStamped
类型所在头文件:
geometry_msgs/PoseStamped.h
常用类成员变量:
- manual_control 订阅遥控器的值
消息名称:
mavros/manual_control/control
类型名称:
mavros_msgs::ManualControl
类型所在头文件:
mavros_msgs::ManualControl.h
- sys_status 查询系统状态
消息名称:
mavros/state
类型名称:
mavros_msgs::State
类型所在头文件:
mavros_msgs/State.h
- waypoint 航点信息
消息名称:
mavros/mission/waypoint
类型名称:
geometry_msgs::WaypointList
类型所在头文件:
mavros_msgs/WaypointList.h
mavros发布消息:
- actuator_control 控制飞控IO输出(混控器)
消息名称:
mavros/actuator_control
类型名称:
geometry_msgs::PoseStamped
类型所在头文件:
mavros_msgs/Actuator_Control.h
常用类成员变量:
- setpoint_accel 控制期望的加速度
消息名称:
mavros/setpoint_accel/accel
类型名称:
geometry_msgs::Vector3Stamped
类型所在的头文件:
geometry_msgs/Vector3Stamped.h
常用类成员变量:
- setpoint_attitude 控制期望的姿态
消息名称:
mavros/setpoint_attitude/attitude
类型名称:
geometry_msgs::PoseStamped
类型所在的头文件:
geometry_msgs/PoseStamped.h
常用类成员变量:
- setpoint_position 控制期望的位置(相对坐标)
消息名称:
mavros/setpoint_position/local
类型名称:
geometry_msgs::PoseStamped
类型所在的头文件:
geometry_msgs/PoseStamped.h
常用类成员变量:
- setpoint_velocity 控制期望的速度
消息名称:
mavros/setpoint_velocity/cmd_vel
类型名称:
geometry_msgs::TwistStamped
类型所在的头文件:
geometry_msgs/TwistStamped.h
常用类成员变量:
- setpoint_position 控制期望的位置(GPS坐标)
消息名称:
mavros/setpoint_position/global
类型名称:
mavros_msgs::GlobalPositionTarget
类型所在的头文件:
mavros_msgs/GlobalPositionTarget.h
常用类成员变量:
mavros服务:
- arming Services 加解锁服务
消息名称:
mavros/cmd/arming
类型名称:
mavros_msgs::CommandBool
类型所在的头文件:
mavros_msgs/CommandBool.h
常用类成员变量:
- 模式切换
消息名称:
mavros/set_mode
类型名称:
mavros_msgs::SetMode
类型所在的头文件:
mavros_msgs/SetMode.h
常用类成员变量:
Loading...