Class providing protocol en/decoding services for the ArduPilot Mega binary telemetry protocol. More...
#include <APM_BinComm.h>
Classes | |
union | _binCommBufferSizer |
struct | MessageHandler |
struct | MessageHeader |
OTA message header. | |
struct | msg_acknowledge |
Structure describing the payload section of the MSG_ACKNOWLEDGE message. More... | |
struct | msg_attitude |
Structure describing the payload section of the MSG_ATTITUDE message. More... | |
struct | msg_attitude_correct |
Structure describing the payload section of the MSG_ATTITUDE_CORRECT message. More... | |
struct | msg_attitude_set |
Structure describing the payload section of the MSG_ATTITUDE_SET message. More... | |
struct | msg_command_list |
Structure describing the payload section of the MSG_COMMAND_LIST message. More... | |
struct | msg_command_mode_change |
Structure describing the payload section of the MSG_COMMAND_MODE_CHANGE message. More... | |
struct | msg_command_request |
Structure describing the payload section of the MSG_COMMAND_REQUEST message. More... | |
struct | msg_command_upload |
Structure describing the payload section of the MSG_COMMAND_UPLOAD message. More... | |
struct | msg_dataflash_request |
Structure describing the payload section of the MSG_DATAFLASH_REQUEST message. More... | |
struct | msg_dataflash_set |
Structure describing the payload section of the MSG_DATAFLASH_SET message. More... | |
struct | msg_eeprom_request |
Structure describing the payload section of the MSG_EEPROM_REQUEST message. More... | |
struct | msg_eeprom_set |
Structure describing the payload section of the MSG_EEPROM_SET message. More... | |
struct | msg_heartbeat |
Structure describing the payload section of the MSG_HEARTBEAT message. More... | |
struct | msg_location |
Structure describing the payload section of the MSG_LOCATION message. More... | |
struct | msg_perf_report |
Structure describing the payload section of the MSG_PERF_REPORT message. More... | |
struct | msg_pid |
Structure describing the payload section of the MSG_PID message. More... | |
struct | msg_pid_request |
Structure describing the payload section of the MSG_PID_REQUEST message. More... | |
struct | msg_pid_set |
Structure describing the payload section of the MSG_PID_SET message. More... | |
struct | msg_pin_request |
Structure describing the payload section of the MSG_PIN_REQUEST message. More... | |
struct | msg_pin_set |
Structure describing the payload section of the MSG_PIN_SET message. More... | |
struct | msg_position_correct |
Structure describing the payload section of the MSG_POSITION_CORRECT message. More... | |
struct | msg_position_set |
Structure describing the payload section of the MSG_POSITION_SET message. More... | |
struct | msg_pressure |
Structure describing the payload section of the MSG_PRESSURE message. More... | |
struct | msg_radio_out |
Structure describing the payload section of the MSG_RADIO_OUT message. More... | |
struct | msg_sensor |
Structure describing the payload section of the MSG_SENSOR message. More... | |
struct | msg_servo_out |
Structure describing the payload section of the MSG_SERVO_OUT message. More... | |
struct | msg_status_text |
Structure describing the payload section of the MSG_STATUS_TEXT message. More... | |
struct | msg_trim_max |
Structure describing the payload section of the MSG_TRIM_MAX message. More... | |
struct | msg_trim_min |
Structure describing the payload section of the MSG_TRIM_MIN message. More... | |
struct | msg_trim_startup |
Structure describing the payload section of the MSG_TRIM_STARTUP message. More... | |
struct | msg_value |
Structure describing the payload section of the MSG_VALUE message. More... | |
struct | msg_value_request |
Structure describing the payload section of the MSG_VALUE_REQUEST message. More... | |
struct | msg_value_set |
Structure describing the payload section of the MSG_VALUE_SET message. More... | |
struct | msg_version |
Structure describing the payload section of the MSG_VERSION message. More... | |
struct | msg_version_request |
Structure describing the payload section of the MSG_VERSION_REQUEST message. More... | |
Public Types | |
enum | MessageID { MSG_PID = 0x42, MSG_DATAFLASH_REQUEST = 0x90, MSG_DATAFLASH_SET = 0x91, MSG_SENSOR = 0x60, MSG_VALUE_REQUEST = 0x30, MSG_VALUE_SET = 0x31, MSG_VALUE = 0x32, MSG_PIN_REQUEST = 0x80, MSG_PIN_SET = 0x81, MSG_POSITION_CORRECT = 0xb0, MSG_ACKNOWLEDGE = 0x0, MSG_ATTITUDE_CORRECT = 0xb1, MSG_HEARTBEAT = 0x1, MSG_POSITION_SET = 0xb2, MSG_ATTITUDE = 0x2, MSG_ATTITUDE_SET = 0xb3, MSG_LOCATION = 0x3, MSG_PRESSURE = 0x4, MSG_TRIM_STARTUP = 0x50, MSG_STATUS_TEXT = 0x5, MSG_TRIM_MIN = 0x51, MSG_PERF_REPORT = 0x6, MSG_TRIM_MAX = 0x52, MSG_VERSION_REQUEST = 0x7, MSG_RADIO_OUT = 0x53, MSG_VERSION = 0x8, MSG_COMMAND_REQUEST = 0x20, MSG_COMMAND_UPLOAD = 0x21, MSG_COMMAND_LIST = 0x22, MSG_COMMAND_MODE_CHANGE = 0x23, MSG_SERVO_OUT = 0x70, MSG_EEPROM_REQUEST = 0xa0, MSG_EEPROM_SET = 0xa1, MSG_PID_REQUEST = 0x40, MSG_PID_SET = 0x41, MSG_ANY = 0xfe, MSG_NULL = 0xff } |
Protocol magic numbers | |
enum | severities { SEVERITY_LOW = 1, SEVERITY_MEDIUM = 2, SEVERITY_HIGH = 3, SEVERITY_CRITICAL = 4 } |
Message serverities. More... | |
enum | variableID { MSG_VAR_ROLL_MODE = 0x00, MSG_VAR_PITCH_MODE = 0x01, MSG_VAR_THROTTLE_MODE = 0x02, MSG_VAR_YAW_MODE = 0x03, MSG_VAR_ELEVON_TRIM_1 = 0x04, MSG_VAR_ELEVON_TRIM_2 = 0x05, MSG_VAR_INTEGRATOR_0 = 0x10, MSG_VAR_INTEGRATOR_1 = 0x11, MSG_VAR_INTEGRATOR_2 = 0x12, MSG_VAR_INTEGRATOR_3 = 0x13, MSG_VAR_INTEGRATOR_4 = 0x14, MSG_VAR_INTEGRATOR_5 = 0x15, MSG_VAR_INTEGRATOR_6 = 0x16, MSG_VAR_INTEGRATOR_7 = 0x17, MSG_VAR_KFF_0 = 0x1a, MSG_VAR_KFF_1 = 0x1b, MSG_VAR_KFF_2 = 0x1c, MSG_VAR_TARGET_BEARING = 0x20, MSG_VAR_NAV_BEARING = 0x21, MSG_VAR_BEARING_ERROR = 0x22, MSG_VAR_CROSSTRACK_BEARING = 0x23, MSG_VAR_CROSSTRACK_ERROR = 0x24, MSG_VAR_ALTITUDE_ERROR = 0x25, MSG_VAR_WP_RADIUS = 0x26, MSG_VAR_LOITER_RADIUS = 0x27, MSG_VAR_WP_MODE = 0x28, MSG_VAR_LOOP_COMMANDS = 0x29, MSG_VAR_NAV_GAIN_SCALER = 0x2a } |
enum | PIDSet { MSG_SERVO_ROLL = 0, MSG_SERVO_PITCH = 1, MSG_SERVO_RUDDER = 2, MSG_SERVO_NAV_ROLL = 3, MSG_SERVO_NAV_PITCH_ASP = 4, MSG_SERVO_NAV_PITCH_ALT = 5, MSG_SERVO_TE_THROTTLE = 6, MSG_SERVO_ALT_THROTTLE = 7, MSG_SERVO_ELEVATOR = 8 } |
PID sets defined. More... | |
Public Member Functions | |
BinComm (const MessageHandler *handlerTable, Stream *interface=NULL) | |
void | init (Stream *interface) |
MSG_ACKNOWLEDGE | |
void | send_msg_acknowledge (const uint8_t msgID, const uint8_t sum1, const uint8_t sum2) |
Send a MSG_ACKNOWLEDGE message. | |
void | unpack_msg_acknowledge (uint8_t &msgID, uint8_t &sum1, uint8_t &sum2) |
Unpack a MSG_ACKNOWLEDGE message. | |
MSG_STATUS_TEXT | |
void | send_msg_status_text (const uint8_t severity, const char(&text)[50]) |
Send a MSG_STATUS_TEXT message. | |
void | unpack_msg_status_text (uint8_t &severity, char(&text)[50]) |
Unpack a MSG_STATUS_TEXT message. | |
MSG_HEARTBEAT | |
void | send_msg_heartbeat (const uint8_t flightMode, const uint16_t timeStamp, const uint16_t batteryVoltage, const uint16_t commandIndex) |
Send a MSG_HEARTBEAT message. | |
void | unpack_msg_heartbeat (uint8_t &flightMode, uint16_t &timeStamp, uint16_t &batteryVoltage, uint16_t &commandIndex) |
Unpack a MSG_HEARTBEAT message. | |
MSG_ATTITUDE | |
void | send_msg_attitude (const int16_t roll, const int16_t pitch, const uint16_t yaw) |
Send a MSG_ATTITUDE message. | |
void | unpack_msg_attitude (int16_t &roll, int16_t &pitch, uint16_t &yaw) |
Unpack a MSG_ATTITUDE message. | |
MSG_LOCATION | |
void | send_msg_location (const int32_t latitude, const int32_t longitude, const int32_t altitude, const uint16_t groundSpeed, const uint16_t groundCourse, const uint32_t timeOfWeek) |
Send a MSG_LOCATION message. | |
void | unpack_msg_location (int32_t &latitude, int32_t &longitude, int32_t &altitude, uint16_t &groundSpeed, uint16_t &groundCourse, uint32_t &timeOfWeek) |
Unpack a MSG_LOCATION message. | |
MSG_PRESSURE | |
void | send_msg_pressure (const int32_t pressureAltitude, const int16_t airSpeed) |
Send a MSG_PRESSURE message. | |
void | unpack_msg_pressure (int32_t &pressureAltitude, int16_t &airSpeed) |
Unpack a MSG_PRESSURE message. | |
MSG_PERF_REPORT | |
void | send_msg_perf_report (const uint32_t interval, const uint16_t mainLoopCycles, const uint8_t mainLoopCycleTime, const uint8_t gyroSaturationCount, const uint8_t adcConstraintCount, const uint8_t renormSqrtCount, const uint8_t renormBlowupCount, const uint8_t gpsFixCount, const uint16_t imuHealth, const uint16_t gcsMessageCount) |
Send a MSG_PERF_REPORT message. | |
void | unpack_msg_perf_report (uint32_t &interval, uint16_t &mainLoopCycles, uint8_t &mainLoopCycleTime, uint8_t &gyroSaturationCount, uint8_t &adcConstraintCount, uint8_t &renormSqrtCount, uint8_t &renormBlowupCount, uint8_t &gpsFixCount, uint16_t &imuHealth, uint16_t &gcsMessageCount) |
Unpack a MSG_PERF_REPORT message. | |
MSG_VERSION_REQUEST | |
void | send_msg_version_request (const uint8_t systemType, const uint8_t systemID) |
Send a MSG_VERSION_REQUEST message. | |
void | unpack_msg_version_request (uint8_t &systemType, uint8_t &systemID) |
Unpack a MSG_VERSION_REQUEST message. | |
MSG_VERSION | |
void | send_msg_version (const uint8_t systemType, const uint8_t systemID, const uint8_t(&firmwareVersion)[3]) |
Send a MSG_VERSION message. | |
void | unpack_msg_version (uint8_t &systemType, uint8_t &systemID, uint8_t(&firmwareVersion)[3]) |
Unpack a MSG_VERSION message. | |
MSG_COMMAND_REQUEST | |
void | send_msg_command_request (const uint16_t UNSPECIFIED) |
Send a MSG_COMMAND_REQUEST message. | |
void | unpack_msg_command_request (uint16_t &UNSPECIFIED) |
Unpack a MSG_COMMAND_REQUEST message. | |
MSG_COMMAND_UPLOAD | |
void | send_msg_command_upload (const uint8_t action, const uint16_t itemNumber, const uint16_t listLength, const uint8_t commandID, const uint8_t p1, const int32_t p2, const int32_t p3, const int32_t p4) |
Send a MSG_COMMAND_UPLOAD message. | |
void | unpack_msg_command_upload (uint8_t &action, uint16_t &itemNumber, uint16_t &listLength, uint8_t &commandID, uint8_t &p1, int32_t &p2, int32_t &p3, int32_t &p4) |
Unpack a MSG_COMMAND_UPLOAD message. | |
MSG_COMMAND_LIST | |
void | send_msg_command_list (const uint16_t itemNumber, const uint16_t listLength, const uint8_t commandID, const uint8_t p1, const int32_t p2, const int32_t p3, const int32_t p4) |
Send a MSG_COMMAND_LIST message. | |
void | unpack_msg_command_list (uint16_t &itemNumber, uint16_t &listLength, uint8_t &commandID, uint8_t &p1, int32_t &p2, int32_t &p3, int32_t &p4) |
Unpack a MSG_COMMAND_LIST message. | |
MSG_COMMAND_MODE_CHANGE | |
void | send_msg_command_mode_change (const uint16_t UNSPECIFIED) |
Send a MSG_COMMAND_MODE_CHANGE message. | |
void | unpack_msg_command_mode_change (uint16_t &UNSPECIFIED) |
Unpack a MSG_COMMAND_MODE_CHANGE message. | |
MSG_VALUE_REQUEST | |
void | send_msg_value_request (const uint8_t valueID, const uint8_t broadcast) |
Send a MSG_VALUE_REQUEST message. | |
void | unpack_msg_value_request (uint8_t &valueID, uint8_t &broadcast) |
Unpack a MSG_VALUE_REQUEST message. | |
MSG_VALUE_SET | |
void | send_msg_value_set (const uint8_t valueID, const uint32_t value) |
Send a MSG_VALUE_SET message. | |
void | unpack_msg_value_set (uint8_t &valueID, uint32_t &value) |
Unpack a MSG_VALUE_SET message. | |
MSG_VALUE | |
void | send_msg_value (const uint8_t valueID, const uint32_t value) |
Send a MSG_VALUE message. | |
void | unpack_msg_value (uint8_t &valueID, uint32_t &value) |
Unpack a MSG_VALUE message. | |
MSG_PID_REQUEST | |
void | send_msg_pid_request (const uint8_t pidSet) |
Send a MSG_PID_REQUEST message. | |
void | unpack_msg_pid_request (uint8_t &pidSet) |
Unpack a MSG_PID_REQUEST message. | |
MSG_PID_SET | |
void | send_msg_pid_set (const uint8_t pidSet, const int32_t p, const int32_t i, const int32_t d, const int16_t integratorMax) |
Send a MSG_PID_SET message. | |
void | unpack_msg_pid_set (uint8_t &pidSet, int32_t &p, int32_t &i, int32_t &d, int16_t &integratorMax) |
Unpack a MSG_PID_SET message. | |
MSG_PID | |
void | send_msg_pid (const uint8_t pidSet, const int32_t p, const int32_t i, const int32_t d, const int16_t integratorMax) |
Send a MSG_PID message. | |
void | unpack_msg_pid (uint8_t &pidSet, int32_t &p, int32_t &i, int32_t &d, int16_t &integratorMax) |
Unpack a MSG_PID message. | |
MSG_TRIM_STARTUP | |
void | send_msg_trim_startup (const uint16_t(&value)[8]) |
Send a MSG_TRIM_STARTUP message. | |
void | unpack_msg_trim_startup (uint16_t(&value)[8]) |
Unpack a MSG_TRIM_STARTUP message. | |
MSG_TRIM_MIN | |
void | send_msg_trim_min (const uint16_t(&value)[8]) |
Send a MSG_TRIM_MIN message. | |
void | unpack_msg_trim_min (uint16_t(&value)[8]) |
Unpack a MSG_TRIM_MIN message. | |
MSG_TRIM_MAX | |
void | send_msg_trim_max (const uint16_t(&value)[8]) |
Send a MSG_TRIM_MAX message. | |
void | unpack_msg_trim_max (uint16_t(&value)[8]) |
Unpack a MSG_TRIM_MAX message. | |
MSG_RADIO_OUT | |
void | send_msg_radio_out (const uint16_t(&value)[8]) |
Send a MSG_RADIO_OUT message. | |
void | unpack_msg_radio_out (uint16_t(&value)[8]) |
Unpack a MSG_RADIO_OUT message. | |
MSG_SENSOR | |
void | send_msg_sensor (const uint16_t UNSPECIFIED) |
Send a MSG_SENSOR message. | |
void | unpack_msg_sensor (uint16_t &UNSPECIFIED) |
Unpack a MSG_SENSOR message. | |
MSG_SERVO_OUT | |
void | send_msg_servo_out (const int16_t(&value)[8]) |
Send a MSG_SERVO_OUT message. | |
void | unpack_msg_servo_out (int16_t(&value)[8]) |
Unpack a MSG_SERVO_OUT message. | |
MSG_PIN_REQUEST | |
void | send_msg_pin_request (const uint16_t UNSPECIFIED) |
Send a MSG_PIN_REQUEST message. | |
void | unpack_msg_pin_request (uint16_t &UNSPECIFIED) |
Unpack a MSG_PIN_REQUEST message. | |
MSG_PIN_SET | |
void | send_msg_pin_set (const uint16_t UNSPECIFIED) |
Send a MSG_PIN_SET message. | |
void | unpack_msg_pin_set (uint16_t &UNSPECIFIED) |
Unpack a MSG_PIN_SET message. | |
MSG_DATAFLASH_REQUEST | |
void | send_msg_dataflash_request (const uint16_t UNSPECIFIED) |
Send a MSG_DATAFLASH_REQUEST message. | |
void | unpack_msg_dataflash_request (uint16_t &UNSPECIFIED) |
Unpack a MSG_DATAFLASH_REQUEST message. | |
MSG_DATAFLASH_SET | |
void | send_msg_dataflash_set (const uint16_t UNSPECIFIED) |
Send a MSG_DATAFLASH_SET message. | |
void | unpack_msg_dataflash_set (uint16_t &UNSPECIFIED) |
Unpack a MSG_DATAFLASH_SET message. | |
MSG_EEPROM_REQUEST | |
void | send_msg_eeprom_request (const uint16_t UNSPECIFIED) |
Send a MSG_EEPROM_REQUEST message. | |
void | unpack_msg_eeprom_request (uint16_t &UNSPECIFIED) |
Unpack a MSG_EEPROM_REQUEST message. | |
MSG_EEPROM_SET | |
void | send_msg_eeprom_set (const uint16_t UNSPECIFIED) |
Send a MSG_EEPROM_SET message. | |
void | unpack_msg_eeprom_set (uint16_t &UNSPECIFIED) |
Unpack a MSG_EEPROM_SET message. | |
MSG_POSITION_CORRECT | |
void | send_msg_position_correct (const int16_t latError, const int16_t lonError, const int16_t altError, const int16_t groundSpeedError) |
Send a MSG_POSITION_CORRECT message. | |
void | unpack_msg_position_correct (int16_t &latError, int16_t &lonError, int16_t &altError, int16_t &groundSpeedError) |
Unpack a MSG_POSITION_CORRECT message. | |
MSG_ATTITUDE_CORRECT | |
void | send_msg_attitude_correct (const int16_t rollError, const int16_t pitchError, const int16_t yawError) |
Send a MSG_ATTITUDE_CORRECT message. | |
void | unpack_msg_attitude_correct (int16_t &rollError, int16_t &pitchError, int16_t &yawError) |
Unpack a MSG_ATTITUDE_CORRECT message. | |
MSG_POSITION_SET | |
void | send_msg_position_set (const int32_t latitude, const int32_t longitude, const int32_t altitude, const uint16_t heading) |
Send a MSG_POSITION_SET message. | |
void | unpack_msg_position_set (int32_t &latitude, int32_t &longitude, int32_t &altitude, uint16_t &heading) |
Unpack a MSG_POSITION_SET message. | |
MSG_ATTITUDE_SET | |
void | send_msg_attitude_set (const int16_t roll, const int16_t pitch, const uint16_t yaw) |
Send a MSG_ATTITUDE_SET message. | |
void | unpack_msg_attitude_set (int16_t &roll, int16_t &pitch, uint16_t &yaw) |
Unpack a MSG_ATTITUDE_SET message. | |
Public Attributes | |
uint8_t | bytes [0] |
MessageHeader | header |
uint8_t | payload [256] |
Encoder interface | |
Messages are normally encoded and sent using the send_msg_* functions defined in protocol/protocol.h. For each message type MSG_* there is a corresponding send_msg_* function which will construct and transmit the message. | |
uint32_t | messagesSent |
statistics | |
Decoder interface | |
| |
uint32_t | messagesReceived |
statistics | |
uint32_t | badMessagesReceived |
statistics | |
void | update (void) |
Class providing protocol en/decoding services for the ArduPilot Mega binary telemetry protocol.
The protocol definition, including structures describing messages, MessageID values and helper functions for sending and unpacking messages are automatically generated.
See protocol/protocol.def for a description of the message definitions, and protocol/protocol.h for the generated definitions.
Protocol messages are sent using the send_* functions defined in protocol/protocol.h, and handled on reception by functions defined in the handlerTable array passed to the constructor.
Definition at line 54 of file APM_BinComm.h.
enum BinComm::MessageID |
Message ID values
Definition at line 1421 of file APM_BinComm.h.
enum BinComm::PIDSet |
PID sets defined.
MSG_SERVO_ROLL | |
MSG_SERVO_PITCH | |
MSG_SERVO_RUDDER | |
MSG_SERVO_NAV_ROLL | |
MSG_SERVO_NAV_PITCH_ASP | |
MSG_SERVO_NAV_PITCH_ALT | |
MSG_SERVO_TE_THROTTLE | |
MSG_SERVO_ALT_THROTTLE | |
MSG_SERVO_ELEVATOR |
Definition at line 232 of file APM_BinComm.h.
enum BinComm::severities |
Message serverities.
Definition at line 187 of file APM_BinComm.h.
enum BinComm::variableID |
Variables defined XXX these should probably be handled by the database/MIB?
Definition at line 197 of file APM_BinComm.h.
BinComm::BinComm | ( | const MessageHandler * | handlerTable, | |
Stream * | interface = NULL | |||
) |
Constructor.
handlerTable | Array of callout functions to which received messages will be sent. More than one handler for a given messageID may be registered; handlers are called in the order they appear in the table. A single handler may be registered for more than one message, as the message ID is passed to the handler when it is received. | |
interface | The stream that will be used for telemetry communications. | |
rxBuffSize | Size of receive buffer allocated by interface. This is used to warn for buffer overflow. |
Definition at line 47 of file APM_BinComm.cpp.
void BinComm::init | ( | Stream * | interface | ) |
Optional initialiser.
If the interface stream isn't known at construction time, it can be set here instead.
interface | The stream that will be used for telemetry communications. |
Definition at line 57 of file APM_BinComm.cpp.
void BinComm::send_msg_acknowledge | ( | const uint8_t | msgID, | |
const uint8_t | sum1, | |||
const uint8_t | sum2 | |||
) | [inline] |
Send a MSG_ACKNOWLEDGE message.
Definition at line 22 of file APM_BinComm.h.
void BinComm::send_msg_attitude | ( | const int16_t | roll, | |
const int16_t | pitch, | |||
const uint16_t | yaw | |||
) | [inline] |
Send a MSG_ATTITUDE message.
Definition at line 148 of file APM_BinComm.h.
void BinComm::send_msg_attitude_correct | ( | const int16_t | rollError, | |
const int16_t | pitchError, | |||
const int16_t | yawError | |||
) | [inline] |
Send a MSG_ATTITUDE_CORRECT message.
Definition at line 1300 of file APM_BinComm.h.
void BinComm::send_msg_attitude_set | ( | const int16_t | roll, | |
const int16_t | pitch, | |||
const uint16_t | yaw | |||
) | [inline] |
Send a MSG_ATTITUDE_SET message.
Definition at line 1390 of file APM_BinComm.h.
void BinComm::send_msg_command_list | ( | const uint16_t | itemNumber, | |
const uint16_t | listLength, | |||
const uint8_t | commandID, | |||
const uint8_t | p1, | |||
const int32_t | p2, | |||
const int32_t | p3, | |||
const int32_t | p4 | |||
) | [inline] |
Send a MSG_COMMAND_LIST message.
Definition at line 554 of file APM_BinComm.h.
void BinComm::send_msg_command_mode_change | ( | const uint16_t | UNSPECIFIED | ) | [inline] |
Send a MSG_COMMAND_MODE_CHANGE message.
Definition at line 614 of file APM_BinComm.h.
void BinComm::send_msg_command_request | ( | const uint16_t | UNSPECIFIED | ) | [inline] |
Send a MSG_COMMAND_REQUEST message.
Definition at line 446 of file APM_BinComm.h.
void BinComm::send_msg_command_upload | ( | const uint8_t | action, | |
const uint16_t | itemNumber, | |||
const uint16_t | listLength, | |||
const uint8_t | commandID, | |||
const uint8_t | p1, | |||
const int32_t | p2, | |||
const int32_t | p3, | |||
const int32_t | p4 | |||
) | [inline] |
Send a MSG_COMMAND_UPLOAD message.
Definition at line 483 of file APM_BinComm.h.
void BinComm::send_msg_dataflash_request | ( | const uint16_t | UNSPECIFIED | ) | [inline] |
Send a MSG_DATAFLASH_REQUEST message.
Definition at line 1130 of file APM_BinComm.h.
void BinComm::send_msg_dataflash_set | ( | const uint16_t | UNSPECIFIED | ) | [inline] |
Send a MSG_DATAFLASH_SET message.
Definition at line 1160 of file APM_BinComm.h.
void BinComm::send_msg_eeprom_request | ( | const uint16_t | UNSPECIFIED | ) | [inline] |
Send a MSG_EEPROM_REQUEST message.
Definition at line 1190 of file APM_BinComm.h.
void BinComm::send_msg_eeprom_set | ( | const uint16_t | UNSPECIFIED | ) | [inline] |
Send a MSG_EEPROM_SET message.
Definition at line 1220 of file APM_BinComm.h.
void BinComm::send_msg_heartbeat | ( | const uint8_t | flightMode, | |
const uint16_t | timeStamp, | |||
const uint16_t | batteryVoltage, | |||
const uint16_t | commandIndex | |||
) | [inline] |
Send a MSG_HEARTBEAT message.
Definition at line 101 of file APM_BinComm.h.
void BinComm::send_msg_location | ( | const int32_t | latitude, | |
const int32_t | longitude, | |||
const int32_t | altitude, | |||
const uint16_t | groundSpeed, | |||
const uint16_t | groundCourse, | |||
const uint32_t | timeOfWeek | |||
) | [inline] |
Send a MSG_LOCATION message.
Definition at line 193 of file APM_BinComm.h.
void BinComm::send_msg_perf_report | ( | const uint32_t | interval, | |
const uint16_t | mainLoopCycles, | |||
const uint8_t | mainLoopCycleTime, | |||
const uint8_t | gyroSaturationCount, | |||
const uint8_t | adcConstraintCount, | |||
const uint8_t | renormSqrtCount, | |||
const uint8_t | renormBlowupCount, | |||
const uint8_t | gpsFixCount, | |||
const uint16_t | imuHealth, | |||
const uint16_t | gcsMessageCount | |||
) | [inline] |
Send a MSG_PERF_REPORT message.
Definition at line 293 of file APM_BinComm.h.
void BinComm::send_msg_pid | ( | const uint8_t | pidSet, | |
const int32_t | p, | |||
const int32_t | i, | |||
const int32_t | d, | |||
const int16_t | integratorMax | |||
) | [inline] |
Send a MSG_PID message.
Definition at line 840 of file APM_BinComm.h.
void BinComm::send_msg_pid_request | ( | const uint8_t | pidSet | ) | [inline] |
Send a MSG_PID_REQUEST message.
Definition at line 752 of file APM_BinComm.h.
void BinComm::send_msg_pid_set | ( | const uint8_t | pidSet, | |
const int32_t | p, | |||
const int32_t | i, | |||
const int32_t | d, | |||
const int16_t | integratorMax | |||
) | [inline] |
Send a MSG_PID_SET message.
Definition at line 786 of file APM_BinComm.h.
void BinComm::send_msg_pin_request | ( | const uint16_t | UNSPECIFIED | ) | [inline] |
Send a MSG_PIN_REQUEST message.
Definition at line 1070 of file APM_BinComm.h.
void BinComm::send_msg_pin_set | ( | const uint16_t | UNSPECIFIED | ) | [inline] |
Send a MSG_PIN_SET message.
Definition at line 1100 of file APM_BinComm.h.
void BinComm::send_msg_position_correct | ( | const int16_t | latError, | |
const int16_t | lonError, | |||
const int16_t | altError, | |||
const int16_t | groundSpeedError | |||
) | [inline] |
Send a MSG_POSITION_CORRECT message.
Definition at line 1253 of file APM_BinComm.h.
void BinComm::send_msg_position_set | ( | const int32_t | latitude, | |
const int32_t | longitude, | |||
const int32_t | altitude, | |||
const uint16_t | heading | |||
) | [inline] |
Send a MSG_POSITION_SET message.
Definition at line 1343 of file APM_BinComm.h.
void BinComm::send_msg_pressure | ( | const int32_t | pressureAltitude, | |
const int16_t | airSpeed | |||
) | [inline] |
Send a MSG_PRESSURE message.
Definition at line 249 of file APM_BinComm.h.
void BinComm::send_msg_radio_out | ( | const uint16_t(&) | value[8] | ) | [inline] |
Send a MSG_RADIO_OUT message.
Definition at line 980 of file APM_BinComm.h.
void BinComm::send_msg_sensor | ( | const uint16_t | UNSPECIFIED | ) | [inline] |
Send a MSG_SENSOR message.
Definition at line 1010 of file APM_BinComm.h.
void BinComm::send_msg_servo_out | ( | const int16_t(&) | value[8] | ) | [inline] |
Send a MSG_SERVO_OUT message.
Definition at line 1040 of file APM_BinComm.h.
void BinComm::send_msg_status_text | ( | const uint8_t | severity, | |
const char(&) | text[50] | |||
) | [inline] |
Send a MSG_STATUS_TEXT message.
Definition at line 63 of file APM_BinComm.h.
void BinComm::send_msg_trim_max | ( | const uint16_t(&) | value[8] | ) | [inline] |
Send a MSG_TRIM_MAX message.
Definition at line 950 of file APM_BinComm.h.
void BinComm::send_msg_trim_min | ( | const uint16_t(&) | value[8] | ) | [inline] |
Send a MSG_TRIM_MIN message.
Definition at line 920 of file APM_BinComm.h.
void BinComm::send_msg_trim_startup | ( | const uint16_t(&) | value[8] | ) | [inline] |
Send a MSG_TRIM_STARTUP message.
Definition at line 890 of file APM_BinComm.h.
void BinComm::send_msg_value | ( | const uint8_t | valueID, | |
const uint32_t | value | |||
) | [inline] |
Send a MSG_VALUE message.
Definition at line 717 of file APM_BinComm.h.
void BinComm::send_msg_value_request | ( | const uint8_t | valueID, | |
const uint8_t | broadcast | |||
) | [inline] |
Send a MSG_VALUE_REQUEST message.
Definition at line 645 of file APM_BinComm.h.
void BinComm::send_msg_value_set | ( | const uint8_t | valueID, | |
const uint32_t | value | |||
) | [inline] |
Send a MSG_VALUE_SET message.
Definition at line 681 of file APM_BinComm.h.
void BinComm::send_msg_version | ( | const uint8_t | systemType, | |
const uint8_t | systemID, | |||
const uint8_t(&) | firmwareVersion[3] | |||
) | [inline] |
Send a MSG_VERSION message.
Definition at line 406 of file APM_BinComm.h.
void BinComm::send_msg_version_request | ( | const uint8_t | systemType, | |
const uint8_t | systemID | |||
) | [inline] |
Send a MSG_VERSION_REQUEST message.
Definition at line 369 of file APM_BinComm.h.
void BinComm::unpack_msg_acknowledge | ( | uint8_t & | msgID, | |
uint8_t & | sum1, | |||
uint8_t & | sum2 | |||
) | [inline] |
Unpack a MSG_ACKNOWLEDGE message.
Definition at line 39 of file APM_BinComm.h.
void BinComm::unpack_msg_attitude | ( | int16_t & | roll, | |
int16_t & | pitch, | |||
uint16_t & | yaw | |||
) | [inline] |
Unpack a MSG_ATTITUDE message.
Definition at line 165 of file APM_BinComm.h.
void BinComm::unpack_msg_attitude_correct | ( | int16_t & | rollError, | |
int16_t & | pitchError, | |||
int16_t & | yawError | |||
) | [inline] |
Unpack a MSG_ATTITUDE_CORRECT message.
Definition at line 1317 of file APM_BinComm.h.
void BinComm::unpack_msg_attitude_set | ( | int16_t & | roll, | |
int16_t & | pitch, | |||
uint16_t & | yaw | |||
) | [inline] |
Unpack a MSG_ATTITUDE_SET message.
Definition at line 1407 of file APM_BinComm.h.
void BinComm::unpack_msg_command_list | ( | uint16_t & | itemNumber, | |
uint16_t & | listLength, | |||
uint8_t & | commandID, | |||
uint8_t & | p1, | |||
int32_t & | p2, | |||
int32_t & | p3, | |||
int32_t & | p4 | |||
) | [inline] |
Unpack a MSG_COMMAND_LIST message.
Definition at line 583 of file APM_BinComm.h.
void BinComm::unpack_msg_command_mode_change | ( | uint16_t & | UNSPECIFIED | ) | [inline] |
Unpack a MSG_COMMAND_MODE_CHANGE message.
Definition at line 625 of file APM_BinComm.h.
void BinComm::unpack_msg_command_request | ( | uint16_t & | UNSPECIFIED | ) | [inline] |
Unpack a MSG_COMMAND_REQUEST message.
Definition at line 457 of file APM_BinComm.h.
void BinComm::unpack_msg_command_upload | ( | uint8_t & | action, | |
uint16_t & | itemNumber, | |||
uint16_t & | listLength, | |||
uint8_t & | commandID, | |||
uint8_t & | p1, | |||
int32_t & | p2, | |||
int32_t & | p3, | |||
int32_t & | p4 | |||
) | [inline] |
Unpack a MSG_COMMAND_UPLOAD message.
Definition at line 515 of file APM_BinComm.h.
void BinComm::unpack_msg_dataflash_request | ( | uint16_t & | UNSPECIFIED | ) | [inline] |
Unpack a MSG_DATAFLASH_REQUEST message.
Definition at line 1141 of file APM_BinComm.h.
void BinComm::unpack_msg_dataflash_set | ( | uint16_t & | UNSPECIFIED | ) | [inline] |
Unpack a MSG_DATAFLASH_SET message.
Definition at line 1171 of file APM_BinComm.h.
void BinComm::unpack_msg_eeprom_request | ( | uint16_t & | UNSPECIFIED | ) | [inline] |
Unpack a MSG_EEPROM_REQUEST message.
Definition at line 1201 of file APM_BinComm.h.
void BinComm::unpack_msg_eeprom_set | ( | uint16_t & | UNSPECIFIED | ) | [inline] |
Unpack a MSG_EEPROM_SET message.
Definition at line 1231 of file APM_BinComm.h.
void BinComm::unpack_msg_heartbeat | ( | uint8_t & | flightMode, | |
uint16_t & | timeStamp, | |||
uint16_t & | batteryVoltage, | |||
uint16_t & | commandIndex | |||
) | [inline] |
Unpack a MSG_HEARTBEAT message.
Definition at line 121 of file APM_BinComm.h.
void BinComm::unpack_msg_location | ( | int32_t & | latitude, | |
int32_t & | longitude, | |||
int32_t & | altitude, | |||
uint16_t & | groundSpeed, | |||
uint16_t & | groundCourse, | |||
uint32_t & | timeOfWeek | |||
) | [inline] |
Unpack a MSG_LOCATION message.
Definition at line 219 of file APM_BinComm.h.
void BinComm::unpack_msg_perf_report | ( | uint32_t & | interval, | |
uint16_t & | mainLoopCycles, | |||
uint8_t & | mainLoopCycleTime, | |||
uint8_t & | gyroSaturationCount, | |||
uint8_t & | adcConstraintCount, | |||
uint8_t & | renormSqrtCount, | |||
uint8_t & | renormBlowupCount, | |||
uint8_t & | gpsFixCount, | |||
uint16_t & | imuHealth, | |||
uint16_t & | gcsMessageCount | |||
) | [inline] |
Unpack a MSG_PERF_REPORT message.
Definition at line 331 of file APM_BinComm.h.
void BinComm::unpack_msg_pid | ( | uint8_t & | pidSet, | |
int32_t & | p, | |||
int32_t & | i, | |||
int32_t & | d, | |||
int16_t & | integratorMax | |||
) | [inline] |
Unpack a MSG_PID message.
Definition at line 863 of file APM_BinComm.h.
void BinComm::unpack_msg_pid_request | ( | uint8_t & | pidSet | ) | [inline] |
Unpack a MSG_PID_REQUEST message.
Definition at line 763 of file APM_BinComm.h.
void BinComm::unpack_msg_pid_set | ( | uint8_t & | pidSet, | |
int32_t & | p, | |||
int32_t & | i, | |||
int32_t & | d, | |||
int16_t & | integratorMax | |||
) | [inline] |
Unpack a MSG_PID_SET message.
Definition at line 809 of file APM_BinComm.h.
void BinComm::unpack_msg_pin_request | ( | uint16_t & | UNSPECIFIED | ) | [inline] |
Unpack a MSG_PIN_REQUEST message.
Definition at line 1081 of file APM_BinComm.h.
void BinComm::unpack_msg_pin_set | ( | uint16_t & | UNSPECIFIED | ) | [inline] |
Unpack a MSG_PIN_SET message.
Definition at line 1111 of file APM_BinComm.h.
void BinComm::unpack_msg_position_correct | ( | int16_t & | latError, | |
int16_t & | lonError, | |||
int16_t & | altError, | |||
int16_t & | groundSpeedError | |||
) | [inline] |
Unpack a MSG_POSITION_CORRECT message.
Definition at line 1273 of file APM_BinComm.h.
void BinComm::unpack_msg_position_set | ( | int32_t & | latitude, | |
int32_t & | longitude, | |||
int32_t & | altitude, | |||
uint16_t & | heading | |||
) | [inline] |
Unpack a MSG_POSITION_SET message.
Definition at line 1363 of file APM_BinComm.h.
void BinComm::unpack_msg_pressure | ( | int32_t & | pressureAltitude, | |
int16_t & | airSpeed | |||
) | [inline] |
Unpack a MSG_PRESSURE message.
Definition at line 263 of file APM_BinComm.h.
void BinComm::unpack_msg_radio_out | ( | uint16_t(&) | value[8] | ) | [inline] |
Unpack a MSG_RADIO_OUT message.
Definition at line 991 of file APM_BinComm.h.
void BinComm::unpack_msg_sensor | ( | uint16_t & | UNSPECIFIED | ) | [inline] |
Unpack a MSG_SENSOR message.
Definition at line 1021 of file APM_BinComm.h.
void BinComm::unpack_msg_servo_out | ( | int16_t(&) | value[8] | ) | [inline] |
Unpack a MSG_SERVO_OUT message.
Definition at line 1051 of file APM_BinComm.h.
void BinComm::unpack_msg_status_text | ( | uint8_t & | severity, | |
char(&) | text[50] | |||
) | [inline] |
Unpack a MSG_STATUS_TEXT message.
Definition at line 77 of file APM_BinComm.h.
void BinComm::unpack_msg_trim_max | ( | uint16_t(&) | value[8] | ) | [inline] |
Unpack a MSG_TRIM_MAX message.
Definition at line 961 of file APM_BinComm.h.
void BinComm::unpack_msg_trim_min | ( | uint16_t(&) | value[8] | ) | [inline] |
Unpack a MSG_TRIM_MIN message.
Definition at line 931 of file APM_BinComm.h.
void BinComm::unpack_msg_trim_startup | ( | uint16_t(&) | value[8] | ) | [inline] |
Unpack a MSG_TRIM_STARTUP message.
Definition at line 901 of file APM_BinComm.h.
void BinComm::unpack_msg_value | ( | uint8_t & | valueID, | |
uint32_t & | value | |||
) | [inline] |
Unpack a MSG_VALUE message.
Definition at line 731 of file APM_BinComm.h.
void BinComm::unpack_msg_value_request | ( | uint8_t & | valueID, | |
uint8_t & | broadcast | |||
) | [inline] |
Unpack a MSG_VALUE_REQUEST message.
Definition at line 659 of file APM_BinComm.h.
void BinComm::unpack_msg_value_set | ( | uint8_t & | valueID, | |
uint32_t & | value | |||
) | [inline] |
Unpack a MSG_VALUE_SET message.
Definition at line 695 of file APM_BinComm.h.
void BinComm::unpack_msg_version | ( | uint8_t & | systemType, | |
uint8_t & | systemID, | |||
uint8_t(&) | firmwareVersion[3] | |||
) | [inline] |
Unpack a MSG_VERSION message.
Definition at line 423 of file APM_BinComm.h.
void BinComm::unpack_msg_version_request | ( | uint8_t & | systemType, | |
uint8_t & | systemID | |||
) | [inline] |
Unpack a MSG_VERSION_REQUEST message.
Definition at line 383 of file APM_BinComm.h.
void BinComm::update | ( | void | ) |
Consume bytes from the interface and feed them to the decoder.
If a packet is completed, then any callbacks associated with the packet's messageID will be called.
If no bytes are passed to the decoder for a period determined by DEC_MESSAGE_TIMEOUT, the decode state machine will reset before processing the next byte. This can help re-synchronise after a link loss or in-flight failure.
Definition at line 100 of file APM_BinComm.cpp.
uint32_t BinComm::badMessagesReceived |
statistics
Definition at line 279 of file APM_BinComm.h.
uint8_t BinComm::bytes[0] |
Definition at line 103 of file APM_BinComm.h.
MessageHeader BinComm::header |
Definition at line 104 of file APM_BinComm.h.
uint32_t BinComm::messagesReceived |
statistics
Definition at line 278 of file APM_BinComm.h.
uint32_t BinComm::messagesSent |
statistics
Definition at line 292 of file APM_BinComm.h.
uint8_t BinComm::payload[256] |
Definition at line 105 of file APM_BinComm.h.