diff options
Diffstat (limited to 'src/modules/mavlink/mavlink_messages.cpp')
-rw-r--r-- | src/modules/mavlink/mavlink_messages.cpp | 120 |
1 files changed, 120 insertions, 0 deletions
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index fef7a5c89..2458dd23a 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -232,6 +232,11 @@ public: return "HEARTBEAT"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_HEARTBEAT; + } + static MavlinkStream *new_instance() { return new MavlinkStreamHeartbeat(); @@ -285,6 +290,11 @@ public: return "SYS_STATUS"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_SYS_STATUS; + } + static MavlinkStream *new_instance() { return new MavlinkStreamSysStatus(); @@ -336,6 +346,11 @@ public: return "HIGHRES_IMU"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_HIGHRES_IMU; + } + static MavlinkStream *new_instance() { return new MavlinkStreamHighresIMU(); @@ -421,6 +436,11 @@ public: return "ATTITUDE"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_ATTITUDE; + } + static MavlinkStream *new_instance() { return new MavlinkStreamAttitude(); @@ -467,6 +487,11 @@ public: return "ATTITUDE_QUATERNION"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_ATTITUDE_QUATERNION; + } + static MavlinkStream *new_instance() { return new MavlinkStreamAttitudeQuaternion(); @@ -519,6 +544,11 @@ public: return "VFR_HUD"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_VFR_HUD; + } + static MavlinkStream *new_instance() { return new MavlinkStreamVFRHUD(); @@ -602,6 +632,11 @@ public: return "GPS_RAW_INT"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_GPS_RAW_INT; + } + static MavlinkStream *new_instance() { return new MavlinkStreamGPSRawInt(); @@ -655,6 +690,11 @@ public: return "GLOBAL_POSITION_INT"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_GLOBAL_POSITION_INT; + } + static MavlinkStream *new_instance() { return new MavlinkStreamGlobalPositionInt(); @@ -716,6 +756,11 @@ public: return "LOCAL_POSITION_NED"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_LOCAL_POSITION_NED; + } + static MavlinkStream *new_instance() { return new MavlinkStreamLocalPositionNED(); @@ -767,6 +812,11 @@ public: return "VICON_POSITION_ESTIMATE"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; + } + static MavlinkStream *new_instance() { return new MavlinkStreamViconPositionEstimate(); @@ -817,6 +867,11 @@ public: return "GPS_GLOBAL_ORIGIN"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; + } + static MavlinkStream *new_instance() { return new MavlinkStreamGPSGlobalOrigin(); @@ -857,6 +912,11 @@ public: return MavlinkStreamServoOutputRaw<N>::get_name_static(); } + uint8_t get_id() + { + return MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; + } + static const char *get_name_static() { switch (N) { @@ -934,6 +994,11 @@ public: return "HIL_CONTROLS"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_HIL_CONTROLS; + } + static MavlinkStream *new_instance() { return new MavlinkStreamHILControls(); @@ -1071,6 +1136,11 @@ public: return "GLOBAL_POSITION_SETPOINT_INT"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; + } + static MavlinkStream *new_instance() { return new MavlinkStreamGlobalPositionSetpointInt(); @@ -1114,6 +1184,11 @@ public: return "LOCAL_POSITION_SETPOINT"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; + } + static MavlinkStream *new_instance() { return new MavlinkStreamLocalPositionSetpoint(); @@ -1162,6 +1237,11 @@ public: return "ROLL_PITCH_YAW_THRUST_SETPOINT"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; + } + static MavlinkStream *new_instance() { return new MavlinkStreamRollPitchYawThrustSetpoint(); @@ -1210,6 +1290,11 @@ public: return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; + } + static MavlinkStream *new_instance() { return new MavlinkStreamRollPitchYawRatesThrustSetpoint(); @@ -1258,6 +1343,11 @@ public: return "RC_CHANNELS_RAW"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_RC_CHANNELS_RAW; + } + static MavlinkStream *new_instance() { return new MavlinkStreamRCChannelsRaw(); @@ -1342,6 +1432,11 @@ public: return "MANUAL_CONTROL"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_MANUAL_CONTROL; + } + static MavlinkStream *new_instance() { return new MavlinkStreamManualControl(); @@ -1391,6 +1486,11 @@ public: return "OPTICAL_FLOW"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_OPTICAL_FLOW; + } + static MavlinkStream *new_instance() { return new MavlinkStreamOpticalFlow(); @@ -1439,6 +1539,11 @@ public: return "ATTITUDE_CONTROLS"; } + uint8_t get_id() + { + return 0; + } + static MavlinkStream *new_instance() { return new MavlinkStreamAttitudeControls(); @@ -1497,6 +1602,11 @@ public: return "NAMED_VALUE_FLOAT"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; + } + static MavlinkStream *new_instance() { return new MavlinkStreamNamedValueFloat(); @@ -1545,6 +1655,11 @@ public: return "CAMERA_CAPTURE"; } + uint8_t get_id() + { + return 0; + } + static MavlinkStream *new_instance() { return new MavlinkStreamCameraCapture(); @@ -1590,6 +1705,11 @@ public: return "DISTANCE_SENSOR"; } + uint8_t get_id() + { + return MAVLINK_MSG_ID_DISTANCE_SENSOR; + } + static MavlinkStream *new_instance() { return new MavlinkStreamDistanceSensor(); |