mavros_msgs¶
Contents:
Summary¶
-
mavros_msgs
¶ Version: 0.14.2
Description: mavros_msgs defines messages for MAVROS.
Maintainers: - Vladimir Ermakov <vooon341 AT gmail DOT com>
Licenses: - GPLv3
- LGPLv3
- BSD
Urls: - website<http://wiki.ros.org/mavros_msgs>
- repository<https://github.com/mavlink/mavros.git>
- bugtracker<https://github.com/mavlink/mavros/issues>
Authors: - Vladimir Ermakov <vooon341 AT gmail DOT com>
BuildDepends: BuildtoolDepends: BuildExportDepends: ExecDepends: Exports: - <architecture_independent/>
Types¶
Message types¶
mavros_msgs/CamIMUStamp
mavros_msgs/ParamValue
mavros_msgs/RCOut
mavros_msgs/ActuatorControl
mavros_msgs/RadioStatus
mavros_msgs/FileEntry
mavros_msgs/VFR_HUD
mavros_msgs/Mavlink
mavros_msgs/CommandCode
mavros_msgs/OverrideRCIn
mavros_msgs/Vibration
mavros_msgs/State
mavros_msgs/BatteryStatus
mavros_msgs/WaypointList
mavros_msgs/RCIn
mavros_msgs/OpticalFlowRad
mavros_msgs/Waypoint
Service types¶
mavros_msgs/ParamPull
mavros_msgs/FileClose
mavros_msgs/FileTruncate
mavros_msgs/CommandBool
mavros_msgs/FileWrite
mavros_msgs/CommandLong
mavros_msgs/FileList
mavros_msgs/CommandHome
mavros_msgs/CommandTriggerControl
mavros_msgs/ParamPush
mavros_msgs/SetMode
mavros_msgs/FileOpen
mavros_msgs/CommandInt
mavros_msgs/FileRead
mavros_msgs/CommandTOL
mavros_msgs/WaypointPull
mavros_msgs/ParamGet
mavros_msgs/FileChecksum
mavros_msgs/WaypointPush
mavros_msgs/ParamSet
mavros_msgs/WaypointClear
mavros_msgs/FileRename
mavros_msgs/FileMakeDir
mavros_msgs/WaypointSetCurrent
mavros_msgs/WaypointGOTO
mavros_msgs/FileRemove
mavros_msgs/StreamRate
mavros_msgs/FileRemoveDir
-
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/FileClose
¶ Field (Request): - file_path (string) –
Field (Response): - success (bool) –
- r_errno (int32) –
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
-
mavros_msgs/FileTruncate
¶ Field (Request): - file_path (string) –
- length (uint64) –
Field (Response): - success (bool) –
- r_errno (int32) –
: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/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/FileWrite
¶ Field (Request): - file_path (string) –
- offset (uint64) –
- data[] (uint8) –
Field (Response): - success (bool) –
- r_errno (int32) –
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/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/FileList
¶ Field (Request): - dir_path (string) –
Field (Response): - list[] (mavros_msgs/FileEntry) –
- success (bool) –
- r_errno (int32) –
: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/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/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/ParamPush
¶ Field (Response): - success (bool) –
- param_transfered (uint32) –
# Send current send # # Returns success status and param_transfered count --- bool success uint32 param_transfered
-
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
- MAV_MODE_PREFLIGHT (uint8):
-
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) –
: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
- MODE_READ (uint8):
-
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/FileRead
¶ Field (Request): - file_path (string) –
- offset (uint64) –
- size (uint64) –
Field (Response): - data[] (uint8) –
- success (bool) –
- r_errno (int32) –
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/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/WaypointPull
¶ Field (Response): - success (bool) –
- wp_received (uint32) –
# Requests waypoints from device # # Returns success status and received count --- bool success uint32 wp_received
-
mavros_msgs/ParamGet
¶ Field (Request): - param_id (string) –
Field (Response): - success (bool) –
- value (mavros_msgs/ParamValue) –
Request parameter from attached device
# Request parameter from attached device string param_id --- bool success ParamValue value
-
mavros_msgs/FileChecksum
¶ Field (Request): - file_path (string) –
Field (Response): - crc32 (uint32) –
- success (bool) –
- r_errno (int32) –
: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/WaypointPush
¶ Field (Request): - waypoints[] (mavros_msgs/Waypoint) –
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/ParamSet
¶ Field (Request): - param_id (string) –
- value (mavros_msgs/ParamValue) –
Field (Response): - success (bool) –
- value (mavros_msgs/ParamValue) –
Request set parameter value
# Request set parameter value string param_id mavros_msgs/ParamValue value --- bool success mavros_msgs/ParamValue value
-
mavros_msgs/WaypointClear
¶ Field (Response): - success (bool) –
# Request clear waypoint --- bool success
-
mavros_msgs/FileRename
¶ Field (Request): - old_path (string) –
- new_path (string) –
Field (Response): - success (bool) –
- r_errno (int32) –
: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) –
: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/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/WaypointGOTO
¶ Field (Request): - waypoint (mavros_msgs/Waypoint) –
Field (Response): - success (bool) –
Request go to waypoint
Only supported FCU will return result
# Request go to waypoint # # Only supported FCU will return result mavros_msgs/Waypoint waypoint --- bool success
-
mavros_msgs/FileRemove
¶ Field (Request): - file_path (string) –
Field (Response): - success (bool) –
- r_errno (int32) –
: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 ---
- STREAM_ALL (uint8):
-
mavros_msgs/FileRemoveDir
¶ Field (Request): - dir_path (string) –
Field (Response): - success (bool) –
- r_errno (int32) –
: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