RedEdge Serial API
This document describes the protocol which can be be used by software to control the RedEdge multi-spectral camera. The camera can be controlled using serial via the host connector. For more detailed information the physical connection to the camera, see the RedEdge Integration Guide on the Downloads page of ATLAS.
Table of Contents
General Protocol Overview
The API is accessed via serial messages in the Mavlink format (see http://en.wikipedia.org/wiki/MAVLink and https://mavlink.io/en/about/overview.html). Mavlink provides an open data format for interaction as well as a suite of tools to assist the programmer in developing and testing the interface. RedEdge uses Mavlink v1.0 messages and communicates with the host at 57600 baud.
Communicating
The HEARTBEAT message can ensure that the RedEdge is booted and ready to receive MAVLink packets.
The PING message can be used to ensure round-trip serial connectivity with the RedEdge.
MAVLink messages include a sender System ID (sysid) parameter. The RedEdge will adopt the System ID of any message it receives, and defaults to 255 otherwise. Because of this behavior, it also ignores the Target System field, and instead assumes that any target system filtering is handled by the sender.
Many MAVLink messages include a Target Component parameter. The RedEdge will ignore any command that does not specify MAV_COMP_ID_CAMERA or MAV_COMP_ID_ALL as the Target Component.
GPS
Receipt of serial state messages will override any RedEdge internal or external sensor data, such as a connected GPS, for 5 seconds since the last state message was received. For aircraft state and mount status, messages should be sent as often as possible to ensure the latest state information is available to the camera when a capture is taken.
There are two supported ways to provide GPS data to the RedEdge. The simplest method is to send the GPS_RAW_INT message, as this single message contains both the time and position information. The other supported way is to send both SYSTEM_TIME and GLOBAL_POSITION_INT together. Sending GPS in both styles at the same time is not recommended.
Commanding Captures
The DIGICAM_CONFIGURE message can be used to set up the camera imagers
The DIGICAM_CONTROL message will command a capture, and the camera will send a CAMERA_STATUS and a CAMERA_FEEDBACK message in response
Parameter Microservice
The parameter microservice implements the MAVLink Parameter Protocol to read or change camera configuration settings.
There are 4 messages associated with the parameter microservice, which are detailed in the Messages section below: PARAM_REQUEST_READ, PARAM_REQUEST_LIST, PARAM_VALUE, PARAM_SET
The enumeration and description of each MAV_PARAM_TYPE is listed below
Value | Field Name | Description |
---|---|---|
1 | MAV_PARAM_TYPE_UINT8 | 8-bit unsigned integer |
2 | MAV_PARAM_TYPE_INT8 | 8-bit signed integer |
3 | MAV_PARAM_TYPE_UINT16 | 16-bit unsigned integer |
4 | MAV_PARAM_TYPE_INT16 | 16-bit signed integer |
5 | MAV_PARAM_TYPE_UINT32 | 32-bit unsigned integer |
6 | MAV_PARAM_TYPE_INT32 | 32-bit signed integer |
7 | MAV_PARAM_TYPE_UINT64 | 64-bit unsigned integer |
8 | MAV_PARAM_TYPE_INT64 | 64-bit signed integer |
9 | MAV_PARAM_TYPE_REAL32 | 32-bit floating point |
10 | MAV_PARAM_TYPE_REAL64 | 64-bit floating point |
Supported Parameters
Param ID | Param Type | Description | Versions | ||||||||
---|---|---|---|---|---|---|---|---|---|---|---|
wifi | MAV_PARAM_TYPE_REAL32 |
|
v1.5.30- | ||||||||
rawFormat | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
enabledBandsRaw | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
enabledBandsJpeg | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
autoCapMode | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
timerPeriod | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- | ||||||||
overlapAlongTrk | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
overlapCrossTrk | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
pwmTriggerThresh | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- | ||||||||
extTriggerMode | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
extTrgrOutPulseH | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- | ||||||||
agcMinimumMean | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- | ||||||||
gainExpCrossover | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- | ||||||||
operatingAlt | MAV_PARAM_TYPE_INT32 |
|
v7.1.0- | ||||||||
opAltTolerance | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
audioEnable | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- | ||||||||
audioSelBitfield | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
injectedGpsDelay | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- | ||||||||
ipAddress | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
pinModes | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
networkMode | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- | ||||||||
thermalNucTime | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- | ||||||||
thermalNucTemp | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- |
WARNING: The parameters below, all prefixed with a "~", are depreciated and may not be supported in future camera software versions. They are read-only, and any PARAM_SET calls will have no effect on the returned value or operation of the camera.
Param ID | Param Type | Description | Versions |
---|---|---|---|
~sdGbFree | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- |
~sdGbTotal | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- |
~sdWarn | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- |
~sdStatus | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- |
~busVolts | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- |
~autoCapActive | MAV_PARAM_TYPE_REAL32 |
|
v7.1.0- |
~dlsStatus | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- |
~timeSource | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- |
~serialFirstFour | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- |
~swVersion | MAV_PARAM_TYPE_UINT32 |
|
v7.1.0- |
Messages
HEARTBEAT (0)
Versions: v1.3.2-
The RedEdge will send a heartbeat message approximately once per second using the component ID MAV_COMP_ID_CAMERA. While this message can be safely ignored, it can be used to verify the RedEdge is properly powered on.
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Type | uint8_t | Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) | Sent as 0 (ignored) |
Autopilot | uint8_t |
|
Sent as 1 (ignored) |
Base Mode | uint8_t |
|
Sent as 2 (ignored) |
Custom Mode | uint32_t | A bitfield for use for autopilot-specific flags. | Sent as 3 (ignored) |
System Status | uint8_t |
|
Sent as 4 (ignored) |
MAVLink Version | uint8_t | MAVLink version, not writable by user | Same as official |
PING (4)
Versions: v1.3.2-
Send the PING message with system_id = 0 and component_id = 0, and with a new sequence number each time, to ensure round-trip communications with the RedEdge. The PING message will be responded to with the same sequence number and the system_id and component_id of the sender (which are present in the message header).
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Time Unix | uint64_t | Timestamp (microseconds since UNIX epoch or microseconds since system boot) | Ignored |
Sequence | uint32_t | PING sequence | Same as official |
System ID | uint8_t | 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system | See description above |
Component ID | uint8_t | 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system | See description above |
GPS_RAW_INT (24)
Versions: v1.3.2-
Use this message to send the raw GPS information to the RedEdge as received by the host vehicle. This is the main message providing GPS information to the RedEdge. Forwarding GPS data to the camera as soon as it is received by the host will ensure the latest information is present in a new capture. Use the 64-bit time_usec field to set the camera's UTC time.
UNIX time is separate from GPS time by a fixed base epoch offset and a changing number of leap seconds (a value that most GPS receivers provide). The base offset is +315964800 seconds between UNIX time and GPS time (UNIX is referenced to 1970-Jan-1 while GPS is referenced to 1980-Jan-6).
Most GPS receivers provide a UTC time message, but it may or may not be microseconds referenced to the Unix epoch, which is what we want. However, most of them provide GPS week number (WN) plus time of week (TOW), plus number of leap seconds (LS), which makes the math easier for embedded processors.
With those GPS time inputs, UNIX epoch UTC times can be calculated by:
Base offset + (GPS Week Number * Seconds in week) + GPS Time of Week - Leap Seconds. 315964800 + ( WN * 604800 ) + TOW - LS
As of 2019 May 05, LS equals 18.
Depending on the receiver/formatting/etc. it may be required to also add in a nanoseconds term to get sub-second resolution.
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Time Unix | uint64_t | Timestamp (microseconds since UNIX epoch or microseconds since system boot) | Same as official |
Fix Type | uint8_t |
|
<= 2: no fix
> 2: 3D fix |
Latitude | int32_t | Latitude (WGS84), in degrees * 1E7 | Same as official |
Longitude | int32_t | Longitude (WGS84), in degrees * 1E7 | Same as official |
Altitude (MSL) | int32_t | Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). | Same as official |
Estimated Position Horizontal | uint16_t | GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX | Same as official |
Estimated Position Vertical | uint16_t | GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX | Same as official |
Speed | uint16_t | GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX | Same as official |
Course Over Ground | uint16_t | Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX | Same as official |
Satellites Visible | uint8_t | Number of satellites visible. If unknown, set to 255 | Same as official |
SYSTEM_TIME (2)
Versions: v1.3.2-
This message is required if using GLOBAL_POSITION_INT, as that message does not provide a UTC timestamp. It is used to update UTC time to provide accurate timestamping of images. Provide a 64-bit unix timestamp referenced to UTC time and the UNIX (not GPS) epoch. Most GPS receivers provide this information in a UTC time message.
Note: if using GPS_RAW_INT, the 64bit timestamp should be set to UTC time prior to sending.
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Time Unix | uint64_t | Timestamp of the master clock in microseconds since UNIX epoch. | Same as official |
Time Boot | uint32_t | Timestamp of the component clock since boot time in milliseconds. | Ignored |
ATTITUDE (30)
Versions: v1.3.2-
Vehicle state (roll, pitch, yaw) and vehicle rates can be provided via the ATTITUDE message. Note that this is the state of the host vehicle. The offset of the camera from the host reference frame, whether fixed or on a gimbals, should be provided via the MOUNT_STATUS message defined below.
The aircraft orientation is specified in the standard aeronautical coordinate frame, where the X axis points to the front of the vehicle, the Y axis points to the right, and the Z axis points down. Rotation order is Yaw, then Pitch, then Roll, about the Z, Y, then X axes accordingly.
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Time Boot | uint32_t | Timestamp (milliseconds since system boot) | Ignored |
Roll | single precision float | Roll angle (rad, -pi..+pi) | Same as official |
Pitch | single precision float | Pitch angle (rad, -pi..+pi) | Same as official |
Yaw | single precision float | Yaw angle (rad, -pi..+pi) | Same as official |
Roll Rate | single precision float | Roll angular velocity (rad/s) | Ignored |
Pitch Rate | single precision float | Pitch angular velocity (rad/s) | Ignored |
Yaw Rate | single precision float | Yaw angular velocity (rad/s) | Ignored |
MOUNT_STATUS (158)
Versions: v1.3.2-
This message can be used to provide the orientation of the camera measured by an external source by sending the MOUNT_STATUS message along with the ATTITUDE message. Anytime this value has been written in the preceding 5 seconds, it will be considered valied and will be written to image metadata.
Using these two messages, two rotations can be specified: An aircraft orientation and a camera orientation. The aircraft orientation gives the orientation of the aircraft relative to the earth frame, and the camera orientation gives the orentiation of the fixed or gimbaled camera relative to the aircraft. If the camera is fixed mounted, the camera orientation can be set to the appropriate static value and only the aircraft orientation needs to be updated.
The camera orientation represents the orientation of the camera relative to the aircraft. The default orientation, when the camera angles are all zero, is defined such that the camera is pointed straight down relative to the aircraft (aircraft nadir) with the top of the camera towards the "front" of the aircraft. The rotation order is again yaw, then pitch, then roll, about the camera Z, Y, and X axes accordingly. The camera axes are defined such that at zero rotation angle, the X axis points down (along the camera focal axis) the Z axis points towards the rear of the vehicle, and the Y axis follows right-hand rule and points out the right side of the vehicle.
The default value for these angles is zero. For a fixed camera pointed straight down relative to the aircraft, and with the top of the camera toward the front of the aircraft, this default value can be used (pitch = 0.0, roll = 0.0, yaw = 0.0).
The combination of the aircraft attitude sent in the attitude message and the rotations in the mount status message will be used to derive an earth-fixed camera orientation. It is recommended that when these messages are built on the host aircraft, the values for both the aircraft orientation and the gimbals orientation are latched into memory, then they are sent via these messages. This will ensure that the aircraft orientation and gimbals orientations were acquired at the same moment.
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
pointing_a | int32_t | Pitch (deg*100) | Same as official |
pointing_b | int32_t | Roll (deg*100) | Same as official |
pointing_c | int32_t | Yaw (deg*100) | Same as official |
Target System | uint8_t | System ID | Ignored |
Target Component | uint8_t | Component ID | Same as official |
GLOBAL_POSITION_INT (33)
Versions: v1.3.2-
Used to update the position from a host state estimate using more than raw GPS, such as a GPS-aided INS system. This may not be the position provided by the GPS receiver, but may be more accurate and/or updated more frequently. Since this message does not have a fix status field, sending it will imply a 3D GPS fix.
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Time Boot | uint32_t | Timestamp (milliseconds since system boot) | Ignored |
Latitude | int32_t | Latitude, expressed as * 1E7 | Same as official |
Longitude | int32_t | Longitude, expressed as * 1E7 | Same as official |
Altitude (MSL) | int32_t | Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) | Same as official |
Altitude (Relative) | int32_t | Altitude above ground in meters, expressed as * 1000 (millimeters) | Ignored |
Velocity X | int16_t | Ground X Speed (Latitude), expressed as m/s * 100 | Same as official |
Velocity Y | int16_t | Ground Y Speed (Longitude), expressed as m/s * 100 | Same as official |
Velocity Z | int16_t | Ground Z Speed (Altitude), expressed as m/s * 100 | Same as official |
Heading | uint16_t | Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX | Ignored |
GPS_STATUS (25)
Versions: v1.3.2-
GPS satellite information which is updated on the RedEdge WiFi user interface. This message is not required, but if sent the GPS status bars on the RedEdge WiFi interface will be updated.
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Satellites Visible | uint8_t | Number of satellites visible | Same as official |
Satellite PRN | uint8_t[20] | Global satellite ID | Same as official |
Satellite Used | uint8_t[20] |
|
Same as official |
Satellite Elevation | uint8_t[20] | Elevation of satellite, degrees. 0-90, where 0 is directly above the receiver, 90 is on the horizon | Same as official |
Satellite Azimuth | uint8_t[20] | Direction of satellite, with 0-360 degrees scaled to the range 0-255 | Same as official |
Satellite SNR | uint8_t[20] | Signal to noise ratio of the satellite | Same as official |
DIGICAM_CONFIGURE (154)
Versions: v1.5.5-
NOTE: At some point, MAVLink.io decided to add a MAV_CMD_DO_DIGICAM_CONFIGURE, which, confusingly, does NOT have the same definition or 154 designation as the DIGICAM_CONFIGURE message.
Manual and Automatic mode are global switches and impact all cameras. For this reason, if commanding each imager to different manual settings, ensure that no messages are sent with auto mode enabled or all imagers will switch to auto mode.
The camera can set all of the imagers to manual mode in a single DIGICAM_CONFIGURE message by using the Extra Command value of 255. Alternatively, one DIGICAM_CONFIGURE message can be sent for each imager (numbers 0-4 for a stock camera) with an individual gain and exposure setting for each.
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Mode | uint8_t |
|
|
Shutter Speed | uint16_t | Shutter speed (seconds divisor). For example, to specify 1/60sec, send 60 | As described in the official description Ignored unless Mode set to Manual |
Aperture | uint8_t | Aperture: F stop number | Set to 0 (ignored) |
ISO | uint8_t | Enumeration of ISO number e.g. 80, 100, 200, etc. |
Gain:
|
Exposure Mode | uint8_t | Exposure type enumerator | Set to 0 (ignored) |
Command ID | uint8_t | Command Identity | Set to 0 (ignored) |
Engine Cut-Off | uint8_t | Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) | This is for the aircraft, should be set to the value recommended by the manufacturer (ignored) |
Extra Command | uint8_t | Extra Command | Sensor number (0-4) of which sensor to set manual settings. Set to 255 for all. |
Extra Value | single precision float | Extra Value | Set to 0 (ignored) |
DIGICAM_CONTROL (155)
Versions: v1.5.5-
NOTE: At some point, MAVLink.io decided to add a MAV_CMD_DO_DIGICAM_CONTROL, which, confusingly, does NOT have the same definition or 155 designation as the DIGICAM_CONTROL message.
The DIGICAM_CONTROL message is used to command captures. Only the "Shutter Command" field is currently used, but default values are provided for the other parameters for future API compatibility.
All sensors configured to capture (e.g. via the WiFi /config route) will be captured.
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
On/Off | uint8_t | Session control (on/off or show/hide lens):
|
Set to 1 (ignored) |
Zoom Position | uint8_t | Zoom's absolute position. 2x, 3x, 10x, etc. | Set to 1 (ignored) |
Zoom Step | int8_t | Zooming step value to offset zoom from the current position | Set to 0 (ignored) |
Focus Lock | uint8_t | Focus Locking, Unlocking or Re-locking:
|
Set to 0 (ignored) |
Shutter Command | uint8_t | Shooting command. Any non-zero value triggers the camera |
|
CommandID | uint8_t | Command Identity | Set to 0 (ignored) |
Extra Command | uint8_t | Extra Command | Set to 0 (ignored) |
Extra Value | single precision float | Extra Value | Set to 0 (ignored) |
CAMERA_STATUS (179)
Versions: v1.5.5-
NOTE: At some point, MAVLink.io decided to assign MAV_CMD_DO_SET_HOME to 179, conflicting with the CAMERA_STATUS message's designation. As of v6.0.0 we do not recognize the MAV_CMD_DO_SET_HOME message, and still use 179 for this message.
If a capture is commanded via MAVLink, a CAMERA_STATUS message with event type "TRIGGER" will be sent back on success
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Time | uint64_t | Image timestamp (microseconds since UNIX epoch, according to camera clock) | Same as official |
Target System | uint8_t | System ID | Same as official |
Camera Index | uint8_t | Camera ID | Same as official |
Image Index | uint16_t | Image Index | Capture number commanded by MAVLink (ignores all other captures, such as WiFi, button, and external trigger) |
Event ID | uint8_t |
|
|
P1 | single precision float | Parameter 1 | Sent as 0 |
P2 | single precision float | Parameter 2 | Sent as 0 |
P3 | single precision float | Parameter 3 | Sent as 0 |
P4 | single precision float | Parameter 4 | Sent as 0 |
CAMERA_FEEDBACK (180)
Versions: v1.5.5-
NOTE: At some point, MAVLink.io decided to assign MAV_CMD_DO_SET_PARAMETER to 180, conflicting with the CAMERA_FEEDBACK message's designation. As of v6.0.0 we do not recognize the MAV_CMD_DO_SET_PARAMETER message, and still use 180 for this message.
If a capture is commanded via MAVLink, a CAMERA_FEEDBACK message with "Flags" type "CAMERA_FEEDBACK_CLOSEDLOOP" will be sent back on success
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Time | uint64_t | Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB) | Same as official |
Target System | uint8_t | System ID | Same as official |
Camera Index | uint8_t | Camera ID | Same as official |
Image Index | uint16_t | Image Index | Capture number commanded by MAVLink (ignores all other captures, such as WiFi, button, and external trigger) |
Latitude | int32_t | Latitude in (deg * 1E7) | Same as official |
Longitude | int32_t | Longitude in (deg * 1E7) | Same as official |
Altitude (MSL) | single precision float | Altitude Absolute (meters AMSL) | Same as official |
Altitude Relative | single precision float | Altitude Relative (meters above HOME location) | Altitude (in meters) above estimated ground level |
Roll | single precision float | Camera Roll angle (earth frame, degrees, +-180) | Same as official |
Pitch | single precision float | Camera Pitch angle (earth frame, degrees, +-180) | Same as official |
Yaw | single precision float | Camera Yaw (earth frame, degrees, 0-360, true) | Same as official |
Focal Length | single precision float | Focal Length (mm) | Same as official |
Flags | uint8_t |
|
|
PARAM_REQUEST_READ (20)
Versions: v7.1.0-
Allows for reading of camera configuration settings
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Target System | uint8_t | System ID | Same as official |
Target Component | uint8_t | Component ID | Same as official |
Param ID | char[16] | Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string | Same as official. See the list of Supported Parameters |
Param Index | int_16 | Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) | Same as official. We do not guarantee indices for a specific parameter will be the same for all software versions, so we recommend using the Param ID and setting the Param Index to -1 for the first access of each parameter after power on. The returned index can be safely used on subsequent calls. |
PARAM_REQUEST_LIST (21)
Versions: v7.1.0-
Requests that the camera send the current value for every supported parameter
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Target System | uint8_t | System ID | Same as official |
Target Component | uint8_t | Component ID | Same as official |
PARAM_VALUE (22)
Versions: v7.1.0-
The current value of a parameter, broadcast in response to a request to get one or more parameters (PARAM_REQUEST_READ, PARAM_REQUEST_LIST) or whenever a parameter is set (PARAM_SET).
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Param ID | char[16] | Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string | Same as official. See the list of Supported Parameters |
Param Value | 4 bytes of data | Onboard parameter value | Implemeted as a union. Interpreted as the MAV_PARAM_TYPE listed in the Param Type field under Supported Parameters |
Param Type | uint8_t | Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types | Same as official |
Param Count | uint16 | Total number of onboard parameters | Same as official |
Param Index | uint_16 | Index of this onboard parameter | Same as official |
PARAM_SET (23)
Versions: v1.5.30-
Allows for configuraiton of miscellaneous settings, not already captured by another MAVLink message
Field Name | Type | Official Description | RedEdge Implementation |
---|---|---|---|
Target System | uint8_t | System ID | Same as official |
Target Component | uint8_t | Component ID | Same as official |
Param ID | char[16] | Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string | Same as official. See the list of Supported Parameters |
Param Value | 4 bytes of data | Onboard parameter value | Implemeted as a union. Interpreted as the MAV_PARAM_TYPE listed in the Param Type field under Supported Parameters |
Param Type | uint8_t | Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types | Same as official |