mavros_msgs

Summary

mavros_msgs
Version:

0.16.6

Description:

mavros_msgs defines messages for MAVROS.

Maintainers:
  • Vladimir Ermakov <vooon341 AT gmail DOT com>
Licenses:
  • GPLv3
  • LGPLv3
  • BSD
Urls:
Authors:
  • Vladimir Ermakov <vooon341 AT gmail DOT com>
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:
Exports:
  • <architecture_independent/>

Types

Message types

mavros_msgs/BatteryStatus
Field:
  • header (std_msgs/Header) –
  • voltage (float32) –
  • current (float32) –
  • remaining (float32) –

Represent battery status from SYSTEM_STATUS

To be replaced when sensor_msgs/BatteryState PR will be merged https://github.com/ros/common_msgs/pull/74

# Represent battery status from SYSTEM_STATUS
#
# To be replaced when sensor_msgs/BatteryState PR will be merged
# https://github.com/ros/common_msgs/pull/74

std_msgs/Header header
float32 voltage # [V]
float32 current # [A]
float32 remaining # 0..1
mavros_msgs/CommandCode
Constant:
  • CMD_DO_SET_MODE (uint16):176
  • CMD_DO_JUMP (uint16):177
  • CMD_DO_CHANGE_SPEED (uint16):178
  • CMD_DO_SET_HOME (uint16):179
  • CMD_DO_SET_RELAY (uint16):181
  • CMD_DO_REPEAT_RELAY (uint16):182
  • CMD_DO_SET_SERVO (uint16):183
  • CMD_DO_REPEAT_SERVO (uint16):184
  • CMD_DO_CONTROL_VIDEO (uint16):200
  • CMD_DO_SET_ROI (uint16):201
  • CMD_DO_MOUNT_CONTROL (uint16):205
  • CMD_DO_SET_CAM_TRIGG_DIST (uint16):206
  • CMD_DO_FENCE_ENABLE (uint16):207
  • CMD_DO_PARACHUTE (uint16):208
  • CMD_DO_INVERTED_FLIGHT (uint16):210
  • CMD_DO_MOUNT_CONTROL_QUAT (uint16):220
  • CMD_PREFLIGHT_CALIBRATION (uint16):241
  • CMD_MISSION_START (uint16):300
  • CMD_COMPONENT_ARM_DISARM (uint16):400
  • CMD_START_RX_PAIR (uint16):500
  • CMD_REQUEST_AUTOPILOT_CAPABILITIES (uint16):520
  • CMD_DO_TRIGGER_CONTROL (uint16):2003
  • NAV_WAYPOINT (uint16):16
  • NAV_LOITER_UNLIM (uint16):17
  • NAV_LOITER_TURNS (uint16):18
  • NAV_LOITER_TIME (uint16):19
  • NAV_RETURN_TO_LAUNCH (uint16):20
  • NAV_LAND (uint16):21
  • NAV_TAKEOFF (uint16):22

Some MAV_CMD command codes. Actual meaning and params you may find in MAVLink documentation http://mavlink.org/messages/common#ENUM_MAV_CMD

some common MAV_CMD

# Some MAV_CMD command codes.
# Actual meaning and params you may find in MAVLink documentation
# http://mavlink.org/messages/common#ENUM_MAV_CMD

# some common MAV_CMD
uint16 CMD_DO_SET_MODE = 176
uint16 CMD_DO_JUMP = 177
uint16 CMD_DO_CHANGE_SPEED = 178
uint16 CMD_DO_SET_HOME = 179
uint16 CMD_DO_SET_RELAY = 181
uint16 CMD_DO_REPEAT_RELAY = 182
uint16 CMD_DO_SET_SERVO = 183
uint16 CMD_DO_REPEAT_SERVO = 184
uint16 CMD_DO_CONTROL_VIDEO = 200
uint16 CMD_DO_SET_ROI = 201
uint16 CMD_DO_MOUNT_CONTROL = 205
uint16 CMD_DO_SET_CAM_TRIGG_DIST = 206
uint16 CMD_DO_FENCE_ENABLE = 207
uint16 CMD_DO_PARACHUTE = 208
uint16 CMD_DO_INVERTED_FLIGHT = 210
uint16 CMD_DO_MOUNT_CONTROL_QUAT = 220
uint16 CMD_PREFLIGHT_CALIBRATION = 241
uint16 CMD_MISSION_START = 300
uint16 CMD_COMPONENT_ARM_DISARM = 400
uint16 CMD_START_RX_PAIR = 500
uint16 CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520
uint16 CMD_DO_TRIGGER_CONTROL = 2003

# Waypoint related commands
uint16 NAV_WAYPOINT = 16
uint16 NAV_LOITER_UNLIM = 17
uint16 NAV_LOITER_TURNS = 18
uint16 NAV_LOITER_TIME = 19
uint16 NAV_RETURN_TO_LAUNCH = 20
uint16 NAV_LAND = 21
uint16 NAV_TAKEOFF = 22
mavros_msgs/ExtendedState
Constant:
  • VTOL_STATE_UNDEFINED (uint8):0
  • VTOL_STATE_TRANSITION_TO_FW (uint8):1
  • VTOL_STATE_TRANSITION_TO_MC (uint8):2
  • VTOL_STATE_MC (uint8):3
  • VTOL_STATE_FW (uint8):4
  • LANDED_STATE_UNDEFINED (uint8):0
  • LANDED_STATE_ON_GROUND (uint8):1
  • LANDED_STATE_IN_AIR (uint8):2
Field:
  • header (std_msgs/Header) –
  • vtol_state (uint8) –
  • landed_state (uint8) –

Extended autopilot state

http://mavlink.org/messages/common#EXTENDED_SYS_STATE

# Extended autopilot state
#
# http://mavlink.org/messages/common#EXTENDED_SYS_STATE

uint8 VTOL_STATE_UNDEFINED = 0
uint8 VTOL_STATE_TRANSITION_TO_FW = 1
uint8 VTOL_STATE_TRANSITION_TO_MC = 2
uint8 VTOL_STATE_MC = 3
uint8 VTOL_STATE_FW = 4

uint8 LANDED_STATE_UNDEFINED = 0
uint8 LANDED_STATE_ON_GROUND = 1
uint8 LANDED_STATE_IN_AIR = 2

std_msgs/Header header
uint8 vtol_state
uint8 landed_state
Field:
  • header (std_msgs/Header) –
  • is_valid (bool) –
  • len (uint8) –
  • seq (uint8) –
  • sysid (uint8) –
  • compid (uint8) –
  • msgid (uint8) –
  • checksum (uint16) –
  • payload64[] (uint64) –

Mavlink message transport type.

Used to transport mavlink_message_t via ROS topic

Is_valid:flag meaning that there CRC16 error or message is unknown by libmavconn. You may simply drop all non valid messages. Used for GCS Bridge to transport unknown messages.

Please use mavros_msgs::mavlink::convert() from <mavros_msgs/mavlink_convert.h> to convert between ROS and MAVLink message type

# Mavlink message transport type.
#
# Used to transport mavlink_message_t via ROS topic
#
# :is_valid: flag meaning that there CRC16 error or message is unknown by libmavconn.
#            You may simply drop all non valid messages. Used for GCS Bridge to transport
#            unknown messages.
#
# Please use mavros_msgs::mavlink::convert() from <mavros_msgs/mavlink_convert.h>
# to convert between ROS and MAVLink message type

std_msgs/Header header
bool is_valid

uint8 len
uint8 seq
uint8 sysid
uint8 compid
uint8 msgid
uint16 checksum
uint64[] payload64
mavros_msgs/GlobalPositionTarget
Field:
Constant:
  • FRAME_GLOBAL_INT (uint8):5
  • FRAME_GLOBAL_REL_ALT (uint8):6
  • FRAME_GLOBAL_TERRAIN_ALT (uint8):11
  • IGNORE_LATITUDE (uint16):1
  • IGNORE_LONGITUDE (uint16):2
  • IGNORE_ALTITUDE (uint16):4
  • IGNORE_VX (uint16):8
  • IGNORE_VY (uint16):16
  • IGNORE_VZ (uint16):32
  • IGNORE_AFX (uint16):64
  • IGNORE_AFY (uint16):128
  • IGNORE_AFZ (uint16):256
  • FORCE (uint16):512
  • IGNORE_YAW (uint16):1024
  • IGNORE_YAW_RATE (uint16):2048

Message for SET_POSITION_TARGET_GLOBAL_INT

Some complex system requires all feautures that mavlink message provide. See issue #402, #415.

# Message for SET_POSITION_TARGET_GLOBAL_INT
#
# Some complex system requires all feautures that mavlink
# message provide. See issue #402, #415.

std_msgs/Header header

uint8 coordinate_frame
uint8 FRAME_GLOBAL_INT = 5
uint8 FRAME_GLOBAL_REL_ALT = 6
uint8 FRAME_GLOBAL_TERRAIN_ALT = 11

uint16 type_mask
uint16 IGNORE_LATITUDE = 1	# Position ignore flags
uint16 IGNORE_LONGITUDE = 2
uint16 IGNORE_ALTITUDE = 4
uint16 IGNORE_VX = 8	# Velocity vector ignore flags
uint16 IGNORE_VY = 16
uint16 IGNORE_VZ = 32
uint16 IGNORE_AFX = 64	# Acceleration/Force vector ignore flags
uint16 IGNORE_AFY = 128
uint16 IGNORE_AFZ = 256
uint16 FORCE = 512	# Force in af vector flag
uint16 IGNORE_YAW = 1024
uint16 IGNORE_YAW_RATE = 2048

float64 latitude
float64 longitude
float32 altitude	# in meters, AMSL or above terrain
geometry_msgs/Vector3 velocity
geometry_msgs/Vector3 acceleration_or_force
float32 yaw
float32 yaw_rate
mavros_msgs/RCOut
Field:

RAW Servo out state

# RAW Servo out state

std_msgs/Header header
uint16[] channels
mavros_msgs/HomePosition
Field:

MAVLink message: HOME_POSITION http://mavlink.org/messages/common#HOME_POSITION

# MAVLink message: HOME_POSITION
# http://mavlink.org/messages/common#HOME_POSITION

std_msgs/Header header

float64 latitude	# WGS84
float64 longitude
float32 altitude	# AMSL

geometry_msgs/Vector3 position	# local position
geometry_msgs/Quaternion orientation	# XXX: verify field name (q[4])
geometry_msgs/Vector3 approach	# position of the end of approach vector
mavros_msgs/State
Field:
  • header (std_msgs/Header) –
  • connected (bool) –
  • armed (bool) –
  • guided (bool) –
  • mode (string) –

Current autopilot state

Known modes listed here: http://wiki.ros.org/mavros/CustomModes

# Current autopilot state
#
# Known modes listed here:
# http://wiki.ros.org/mavros/CustomModes

std_msgs/Header header
bool connected
bool armed
bool guided
string mode
mavros_msgs/RadioStatus
Field:
  • header (std_msgs/Header) –
  • rssi (uint8) –
  • remrssi (uint8) –
  • txbuf (uint8) –
  • noise (uint8) –
  • remnoise (uint8) –
  • rxerrors (uint16) –
  • fixed (uint16) –
  • rssi_dbm (float32) –
  • remrssi_dbm (float32) –

RADIO_STATUS message

# RADIO_STATUS message

std_msgs/Header header

# message data
uint8 rssi
uint8 remrssi
uint8 txbuf
uint8 noise
uint8 remnoise
uint16 rxerrors
uint16 fixed

# calculated
float32 rssi_dbm
float32 remrssi_dbm
mavros_msgs/CamIMUStamp
Field:
  • frame_stamp (time) –
  • frame_seq_id (int32) –

IMU-Camera synchronisation data

# IMU-Camera synchronisation data

time frame_stamp		# Timestamp when the camera was triggered
int32 frame_seq_id		# Sequence number of the image frame
mavros_msgs/OverrideRCIn
Constant:
  • CHAN_RELEASE (uint16):0
  • CHAN_NOCHANGE (uint16):65535
Field:
  • channels[8] (uint16) –

Override RC Input Currently MAVLink defines override for 8 channel

# Override RC Input
# Currently MAVLink defines override for 8 channel

uint16 CHAN_RELEASE=0
uint16 CHAN_NOCHANGE=65535

uint16[8] channels
mavros_msgs/ParamValue
Field:
  • integer (int64) –
  • real (float64) –

Parameter value storage type.

Integer and float fields:

if integer != 0: it is integer value else if real != 0.0: it is float value else: it is zero.

# Parameter value storage type.
#
# Integer and float fields:
#
# if integer != 0: it is integer value
# else if real != 0.0: it is float value
# else: it is zero.

int64 integer
float64 real
mavros_msgs/VFR_HUD
Field:
  • header (std_msgs/Header) –
  • airspeed (float32) –
  • groundspeed (float32) –
  • heading (int16) –
  • throttle (float32) –
  • altitude (float32) –
  • climb (float32) –

Metrics typically displayed on a HUD for fixed wing aircraft

VFR_HUD message

# Metrics typically displayed on a HUD for fixed wing aircraft
#
# VFR_HUD message

std_msgs/Header header
float32 airspeed	# m/s
float32 groundspeed	# m/s
int16 heading		# degrees 0..360
float32 throttle		# normalized to 0.0..1.0
float32 altitude		# MSL
float32 climb		# current climb rate m/s
mavros_msgs/RCIn
Field:

RAW RC input state

# RAW RC input state

std_msgs/Header header
uint8 rssi
uint16[] channels
mavros_msgs/WaypointList
Field:
mavros_msgs/Waypoint[] waypoints
mavros_msgs/FileEntry
Constant:
  • TYPE_FILE (uint8):0
  • TYPE_DIRECTORY (uint8):1
Field:
  • name (string) –
  • type (uint8) –
  • size (uint64) –

File/Dir information

# File/Dir information

uint8 TYPE_FILE = 0
uint8 TYPE_DIRECTORY = 1

string name
uint8 type
uint64 size

# Not supported by MAVLink FTP
#time atime
#int32 access_flags
mavros_msgs/ActuatorControl
Constant:
  • PX4_MIX_FLIGHT_CONTROL (uint8):0
  • PX4_MIX_FLIGHT_CONTROL_VTOL_ALT (uint8):1
  • PX4_MIX_PAYLOAD (uint8):2
  • PX4_MIX_MANUAL_PASSTHROUGH (uint8):3
Field:
  • header (std_msgs/Header) –
  • group_mix (uint8) –
  • controls[8] (float32) –

raw servo values for direct actuator controls

about groups, mixing and channels: https://pixhawk.org/dev/mixing

constant for mixer group

# raw servo values for direct actuator controls
#
# about groups, mixing and channels:
# https://pixhawk.org/dev/mixing

# constant for mixer group
uint8 PX4_MIX_FLIGHT_CONTROL = 0
uint8 PX4_MIX_FLIGHT_CONTROL_VTOL_ALT = 1
uint8 PX4_MIX_PAYLOAD = 2
uint8 PX4_MIX_MANUAL_PASSTHROUGH = 3
#uint8 PX4_MIX_FC_MC_VIRT = 4
#uint8 PX4_MIX_FC_FW_VIRT = 5

std_msgs/Header header
uint8 group_mix
float32[8] controls
mavros_msgs/AttitudeTarget
Field:
Constant:
  • IGNORE_ROLL_RATE (uint8):1
  • IGNORE_PITCH_RATE (uint8):2
  • IGNORE_YAW_RATE (uint8):4
  • IGNORE_THRUST (uint8):64
  • IGNORE_ATTITUDE (uint8):128

Message for SET_ATTITUDE_TARGET

Some complex system requires all feautures that mavlink message provide. See issue #402, #418.

# Message for SET_ATTITUDE_TARGET
#
# Some complex system requires all feautures that mavlink
# message provide. See issue #402, #418.

std_msgs/Header header

uint8 type_mask
uint8 IGNORE_ROLL_RATE = 1	# body_rate.x
uint8 IGNORE_PITCH_RATE = 2	# body_rate.y
uint8 IGNORE_YAW_RATE = 4	# body_rate.z
uint8 IGNORE_THRUST = 64
uint8 IGNORE_ATTITUDE = 128	# orientation field

geometry_msgs/Quaternion orientation
geometry_msgs/Vector3 body_rate
float32 thrust
mavros_msgs/ManualControl
Field:
  • header (std_msgs/Header) –
  • x (float32) –
  • y (float32) –
  • z (float32) –
  • r (float32) –
  • buttons (uint16) –

Manual Control state

# Manual Control state
std_msgs/Header header
float32 x
float32 y
float32 z
float32 r
uint16 buttons
mavros_msgs/Altitude
Field:
  • header (std_msgs/Header) –
  • monotonic (float32) –
  • amsl (float32) –
  • local (float32) –
  • relative (float32) –
  • terrain (float32) –
  • bottom_clearance (float32) –

Altitude information

https://pixhawk.ethz.ch/mavlink/#ALTITUDE

# Altitude information
#
# https://pixhawk.ethz.ch/mavlink/#ALTITUDE

std_msgs/Header header

float32 monotonic
float32 amsl
float32 local
float32 relative
float32 terrain
float32 bottom_clearance
mavros_msgs/Vibration
Field:

VIBRATION message data @description: Vibration levels and accelerometer clipping

# VIBRATION message data
# @description: Vibration levels and accelerometer clipping

std_msgs/Header header

geometry_msgs/Vector3 vibration		# 3-axis vibration levels
float32[3] clipping				# Accelerometers clipping
mavros_msgs/PositionTarget
Field:
Constant:
  • FRAME_LOCAL_NED (uint8):1
  • FRAME_LOCAL_OFFSET_NED (uint8):7
  • FRAME_BODY_NED (uint8):8
  • FRAME_BODY_OFFSET_NED (uint8):9
  • IGNORE_PX (uint16):1
  • IGNORE_PY (uint16):2
  • IGNORE_PZ (uint16):4
  • IGNORE_VX (uint16):8
  • IGNORE_VY (uint16):16
  • IGNORE_VZ (uint16):32
  • IGNORE_AFX (uint16):64
  • IGNORE_AFY (uint16):128
  • IGNORE_AFZ (uint16):256
  • FORCE (uint16):512
  • IGNORE_YAW (uint16):1024
  • IGNORE_YAW_RATE (uint16):2048

Message for SET_POSITION_TARGET_LOCAL_NED

Some complex system requires all feautures that mavlink message provide. See issue #402.

# Message for SET_POSITION_TARGET_LOCAL_NED
#
# Some complex system requires all feautures that mavlink
# message provide. See issue #402.

std_msgs/Header header

uint8 coordinate_frame
uint8 FRAME_LOCAL_NED = 1
uint8 FRAME_LOCAL_OFFSET_NED = 7
uint8 FRAME_BODY_NED = 8
uint8 FRAME_BODY_OFFSET_NED = 9

uint16 type_mask
uint16 IGNORE_PX = 1	# Position ignore flags
uint16 IGNORE_PY = 2
uint16 IGNORE_PZ = 4
uint16 IGNORE_VX = 8	# Velocity vector ignore flags
uint16 IGNORE_VY = 16
uint16 IGNORE_VZ = 32
uint16 IGNORE_AFX = 64	# Acceleration/Force vector ignore flags
uint16 IGNORE_AFY = 128
uint16 IGNORE_AFZ = 256
uint16 FORCE = 512	# Force in af vector flag
uint16 IGNORE_YAW = 1024
uint16 IGNORE_YAW_RATE = 2048

geometry_msgs/Point position
geometry_msgs/Vector3 velocity
geometry_msgs/Vector3 acceleration_or_force
float32 yaw
float32 yaw_rate
mavros_msgs/OpticalFlowRad
Field:
  • header (std_msgs/Header) –
  • integration_time_us (uint32) –
  • integrated_x (float32) –
  • integrated_y (float32) –
  • integrated_xgyro (float32) –
  • integrated_ygyro (float32) –
  • integrated_zgyro (float32) –
  • temperature (int16) –
  • quality (uint8) –
  • time_delta_distance_us (uint32) –
  • distance (float32) –

OPTICAL_FLOW_RAD message data

# OPTICAL_FLOW_RAD message data

std_msgs/Header header

uint32 integration_time_us
float32 integrated_x
float32 integrated_y
float32 integrated_xgyro
float32 integrated_ygyro
float32 integrated_zgyro
int16 temperature
uint8 quality
uint32 time_delta_distance_us
float32 distance
mavros_msgs/Waypoint
Field:
  • frame (uint8) –
  • command (uint16) –
  • is_current (bool) –
  • autocontinue (bool) –
  • param1 (float32) –
  • param2 (float32) –
  • param3 (float32) –
  • param4 (float32) –
  • x_lat (float64) –
  • y_long (float64) –
  • z_alt (float64) –
Constant:
  • FRAME_GLOBAL (uint8):0
  • FRAME_LOCAL_NED (uint8):1
  • FRAME_MISSION (uint8):2
  • FRAME_GLOBAL_REL_ALT (uint8):3
  • FRAME_LOCAL_ENU (uint8):4

Waypoint.msg

ROS representation of MAVLink MISSION_ITEM See mavlink documentation

see enum MAV_FRAME

# Waypoint.msg
#
# ROS representation of MAVLink MISSION_ITEM
# See mavlink documentation



# see enum MAV_FRAME
uint8 frame
uint8 FRAME_GLOBAL = 0
uint8 FRAME_LOCAL_NED = 1
uint8 FRAME_MISSION = 2
uint8 FRAME_GLOBAL_REL_ALT = 3
uint8 FRAME_LOCAL_ENU = 4

# see enum MAV_CMD and CommandCode.msg
uint16 command

bool is_current
bool autocontinue
# meaning of this params described in enum MAV_CMD
float32 param1
float32 param2
float32 param3
float32 param4
float64 x_lat
float64 y_long
float64 z_alt

Service types

mavros_msgs/FileRename
Field (Request):
 
  • old_path (string) –
  • new_path (string) –
Field (Response):
 
  • success (bool) –
  • r_errno (int32) –

FTP::Rename

:success: indicates success end of request :r_errno: remote errno if applicapable

# FTP::Rename
#
# :success:	indicates success end of request
# :r_errno:	remote errno if applicapable

string old_path
string new_path
---
bool success
int32 r_errno
mavros_msgs/FileMakeDir
Field (Request):
 
  • dir_path (string) –
Field (Response):
 
  • success (bool) –
  • r_errno (int32) –

FTP::MakeDir

:success: indicates success end of request :r_errno: remote errno if applicapable

# FTP::MakeDir
#
# :success:	indicates success end of request
# :r_errno:	remote errno if applicapable

string dir_path
---
bool success
int32 r_errno
mavros_msgs/SetMode
Constant (Request):
 
  • MAV_MODE_PREFLIGHT (uint8):0
  • MAV_MODE_STABILIZE_DISARMED (uint8):80
  • MAV_MODE_STABILIZE_ARMED (uint8):208
  • MAV_MODE_MANUAL_DISARMED (uint8):64
  • MAV_MODE_MANUAL_ARMED (uint8):192
  • MAV_MODE_GUIDED_DISARMED (uint8):88
  • MAV_MODE_GUIDED_ARMED (uint8):216
  • MAV_MODE_AUTO_DISARMED (uint8):92
  • MAV_MODE_AUTO_ARMED (uint8):220
  • MAV_MODE_TEST_DISARMED (uint8):66
  • MAV_MODE_TEST_ARMED (uint8):194
Field (Request):
 
  • base_mode (uint8) –
  • custom_mode (string) –
Field (Response):
 
  • success (bool) –

set FCU mode

Known custom modes listed here: http://wiki.ros.org/mavros/CustomModes

basic modes from MAV_MODE

# set FCU mode
#
# Known custom modes listed here:
# http://wiki.ros.org/mavros/CustomModes

# basic modes from MAV_MODE
uint8 MAV_MODE_PREFLIGHT		= 0
uint8 MAV_MODE_STABILIZE_DISARMED	= 80
uint8 MAV_MODE_STABILIZE_ARMED		= 208
uint8 MAV_MODE_MANUAL_DISARMED		= 64
uint8 MAV_MODE_MANUAL_ARMED		= 192
uint8 MAV_MODE_GUIDED_DISARMED		= 88
uint8 MAV_MODE_GUIDED_ARMED		= 216
uint8 MAV_MODE_AUTO_DISARMED		= 92
uint8 MAV_MODE_AUTO_ARMED		= 220
uint8 MAV_MODE_TEST_DISARMED		= 66
uint8 MAV_MODE_TEST_ARMED		= 194

uint8 base_mode		# filled by MAV_MODE enum value or 0 if custom_mode != ''
string custom_mode	# string mode representation or integer
---
bool success
mavros_msgs/FileRemoveDir
Field (Request):
 
  • dir_path (string) –
Field (Response):
 
  • success (bool) –
  • r_errno (int32) –

FTP::RemoveDir

:success: indicates success end of request :r_errno: remote errno if applicapable

# FTP::RemoveDir
#
# :success:	indicates success end of request
# :r_errno:	remote errno if applicapable

string dir_path
---
bool success
int32 r_errno
mavros_msgs/FileRemove
Field (Request):
 
  • file_path (string) –
Field (Response):
 
  • success (bool) –
  • r_errno (int32) –

FTP::Remove

:success: indicates success end of request :r_errno: remote errno if applicapable

# FTP::Remove
#
# :success:	indicates success end of request
# :r_errno:	remote errno if applicapable

string file_path
---
bool success
int32 r_errno
mavros_msgs/StreamRate
Constant (Request):
 
  • STREAM_ALL (uint8):0
  • STREAM_RAW_SENSORS (uint8):1
  • STREAM_EXTENDED_STATUS (uint8):2
  • STREAM_RC_CHANNELS (uint8):3
  • STREAM_RAW_CONTROLLER (uint8):4
  • STREAM_POSITION (uint8):6
  • STREAM_EXTRA1 (uint8):10
  • STREAM_EXTRA2 (uint8):11
  • STREAM_EXTRA3 (uint8):12
Field (Request):
 
  • stream_id (uint8) –
  • message_rate (uint16) –
  • on_off (bool) –

sets stream rate See REQUEST_DATA_STREAM message

# sets stream rate
# See REQUEST_DATA_STREAM message

uint8 STREAM_ALL = 0
uint8 STREAM_RAW_SENSORS = 1
uint8 STREAM_EXTENDED_STATUS = 2
uint8 STREAM_RC_CHANNELS = 3
uint8 STREAM_RAW_CONTROLLER = 4
uint8 STREAM_POSITION = 6
uint8 STREAM_EXTRA1 = 10
uint8 STREAM_EXTRA2 = 11
uint8 STREAM_EXTRA3 = 12

uint8 stream_id
uint16 message_rate
bool on_off
---
mavros_msgs/WaypointClear
Field (Response):
 
  • success (bool) –

Request clear waypoint

# Request clear waypoint

---
bool success
mavros_msgs/WaypointPull
Field (Response):
 
  • success (bool) –
  • wp_received (uint32) –

Requests waypoints from device

Returns success status and received count

# Requests waypoints from device
#
# Returns success status and received count

---
bool success
uint32 wp_received
mavros_msgs/CommandBool
Field (Request):
 
  • value (bool) –
Field (Response):
 
  • success (bool) –
  • result (uint8) –

Common type for switch commands

# Common type for switch commands

bool value
---
bool success
uint8 result
mavros_msgs/WaypointSetCurrent
Field (Request):
 
  • wp_seq (uint16) –
Field (Response):
 
  • success (bool) –

Request set current waypoint

wp_seq - index in waypoint array

# Request set current waypoint
#
# wp_seq - index in waypoint array

uint16 wp_seq
---
bool success
mavros_msgs/ParamSet
Field (Request):
 
Field (Response):
 

Request set parameter value

# Request set parameter value

string param_id
mavros_msgs/ParamValue value
---
bool success
mavros_msgs/ParamValue value
mavros_msgs/WaypointPush
Field (Request):
 
Field (Response):
 
  • success (bool) –
  • wp_transfered (uint32) –

Send waypoints to device

Returns success status and transfered count

# Send waypoints to device
#
# Returns success status and transfered count

mavros_msgs/Waypoint[] waypoints
---
bool success
uint32 wp_transfered
mavros_msgs/ParamGet
Field (Request):
 
  • param_id (string) –
Field (Response):
 

Request parameter from attached device

# Request parameter from attached device

string param_id
---
bool success
ParamValue value
mavros_msgs/CommandInt
Field (Request):
 
  • broadcast (bool) –
  • frame (uint8) –
  • command (uint16) –
  • current (uint8) –
  • autocontinue (uint8) –
  • param1 (float32) –
  • param2 (float32) –
  • param3 (float32) –
  • param4 (float32) –
  • x (int32) –
  • y (int32) –
  • z (float32) –
Field (Response):
 
  • success (bool) –

Generic COMMAND_INT

# Generic COMMAND_INT

bool broadcast # send this command in broadcast mode

uint8 frame
uint16 command
uint8 current
uint8 autocontinue
float32 param1
float32 param2
float32 param3
float32 param4
int32 x	# latitude in deg * 1E7 or local x * 1E4 m
int32 y	# longitude in deg * 1E7 or local y * 1E4 m
float32 z	# altitude
---
bool success
# seems that this message don't produce andy COMMAND_ACK messages
# so no result field
mavros_msgs/FileOpen
Constant (Request):
 
  • MODE_READ (uint8):0
  • MODE_WRITE (uint8):1
  • MODE_CREATE (uint8):2
Field (Request):
 
  • file_path (string) –
  • mode (uint8) –
Field (Response):
 
  • size (uint32) –
  • success (bool) –
  • r_errno (int32) –

FTP::Open

:file_path: used as session id in read/write/close services :size: file size returned for MODE_READ :success: indicates success end of request :r_errno: remote errno if applicapable

# FTP::Open
#
# :file_path:	used as session id in read/write/close services
# :size:	file size returned for MODE_READ
# :success:	indicates success end of request
# :r_errno:	remote errno if applicapable

uint8 MODE_READ = 0	# open for read
uint8 MODE_WRITE = 1	# open for write
uint8 MODE_CREATE = 2	# do creat()

string file_path
uint8 mode
---
uint32 size
bool success
int32 r_errno
mavros_msgs/CommandTriggerControl
Field (Request):
 
  • trigger_enable (bool) –
  • integration_time (float32) –
Field (Response):
 
  • success (bool) –
  • result (uint8) –

Type for controlling onboard camera trigerring system

# Type for controlling onboard camera trigerring system

bool    trigger_enable		# Trigger on/off control
float32 integration_time	# Shutter integration time. Zero to use current onboard value.
---
bool success
uint8 result
mavros_msgs/FileWrite
Field (Request):
 
  • file_path (string) –
  • offset (uint64) –
  • data[] (uint8) –
Field (Response):
 
  • success (bool) –
  • r_errno (int32) –

FTP::Write

Call FTP::Open first. :success: indicates success end of request :r_errno: remote errno if applicapable

# FTP::Write
#
# Call FTP::Open first.
# :success:	indicates success end of request
# :r_errno:	remote errno if applicapable

string file_path
uint64 offset
uint8[] data
---
bool success
int32 r_errno
mavros_msgs/CommandTOL
Field (Request):
 
  • min_pitch (float32) –
  • yaw (float32) –
  • latitude (float32) –
  • longitude (float32) –
  • altitude (float32) –
Field (Response):
 
  • success (bool) –
  • result (uint8) –

Common type for Take Off and Landing

# Common type for Take Off and Landing

float32 min_pitch	# used by takeoff
float32 yaw
float32 latitude
float32 longitude
float32 altitude
---
bool success
uint8 result
mavros_msgs/FileTruncate
Field (Request):
 
  • file_path (string) –
  • length (uint64) –
Field (Response):
 
  • success (bool) –
  • r_errno (int32) –

FTP::Truncate

:success: indicates success end of request :r_errno: remote errno if applicapable

# FTP::Truncate
#
# :success:	indicates success end of request
# :r_errno:	remote errno if applicapable

string file_path
uint64 length
---
bool success
int32 r_errno
mavros_msgs/FileChecksum
Field (Request):
 
  • file_path (string) –
Field (Response):
 
  • crc32 (uint32) –
  • success (bool) –
  • r_errno (int32) –

FTP::Checksum

:file_path: file to calculate checksum :crc32: file checksum :success: indicates success end of request :r_errno: remote errno if applicapable

# FTP::Checksum
#
# :file_path:	file to calculate checksum
# :crc32:	file checksum
# :success:	indicates success end of request
# :r_errno:	remote errno if applicapable

string file_path
---
uint32 crc32
bool success
int32 r_errno
mavros_msgs/ParamPull
Field (Request):
 
  • force_pull (bool) –
Field (Response):
 
  • success (bool) –
  • param_received (uint32) –

Request parameters from device

Returns success status and param_recived count

# Request parameters from device
#
# Returns success status and param_recived count

bool force_pull
---
bool success
uint32 param_received
mavros_msgs/CommandHome
Field (Request):
 
  • current_gps (bool) –
  • latitude (float32) –
  • longitude (float32) –
  • altitude (float32) –
Field (Response):
 
  • success (bool) –
  • result (uint8) –

request set new home position

# request set new home position

bool current_gps
float32 latitude
float32 longitude
float32 altitude
---
bool success
uint8 result
mavros_msgs/FileList
Field (Request):
 
  • dir_path (string) –
Field (Response):
 

FTP::List

:success: indicates success end of request :r_errno: remote errno if applicapable

# FTP::List
#
# :success:	indicates success end of request
# :r_errno:	remote errno if applicapable

string dir_path
---
mavros_msgs/FileEntry[] list
bool success
int32 r_errno
mavros_msgs/ParamPush
Field (Response):
 
  • success (bool) –
  • param_transfered (uint32) –

Send current send

Returns success status and param_transfered count

# Send current send
#
# Returns success status and param_transfered count

---
bool success
uint32 param_transfered
mavros_msgs/FileRead
Field (Request):
 
  • file_path (string) –
  • offset (uint64) –
  • size (uint64) –
Field (Response):
 
  • data[] (uint8) –
  • success (bool) –
  • r_errno (int32) –

FTP::Read

Call FTP::Open first. :success: indicates success end of request :r_errno: remote errno if applicapable

# FTP::Read
#
# Call FTP::Open first.
# :success:	indicates success end of request
# :r_errno:	remote errno if applicapable

string file_path
uint64 offset
uint64 size
---
uint8[] data
bool success
int32 r_errno
mavros_msgs/CommandLong
Field (Request):
 
  • broadcast (bool) –
  • command (uint16) –
  • confirmation (uint8) –
  • param1 (float32) –
  • param2 (float32) –
  • param3 (float32) –
  • param4 (float32) –
  • param5 (float32) –
  • param6 (float32) –
  • param7 (float32) –
Field (Response):
 
  • success (bool) –
  • result (uint8) –

Generic COMMAND_LONG

# Generic COMMAND_LONG

bool broadcast # send this command in broadcast mode

uint16 command
uint8 confirmation
float32 param1
float32 param2
float32 param3
float32 param4
float32 param5	# x_lat
float32 param6	# y_lon
float32 param7	# z_alt
---
bool success
# raw result returned by COMMAND_ACK
uint8 result
mavros_msgs/FileClose
Field (Request):
 
  • file_path (string) –
Field (Response):
 
  • success (bool) –
  • r_errno (int32) –

FTP::Close

Call FTP::Open first. :success: indicates success end of request :r_errno: remote errno if applicapable

# FTP::Close
#
# Call FTP::Open first.
# :success:	indicates success end of request
# :r_errno:	remote errno if applicapable

string file_path
---
bool success
int32 r_errno