forked from Archive/PX4-Autopilot
templated creation of stream list items
and constexpr for get_id_static and get_name_static in mavlink streams
This commit is contained in:
parent
f57c5ef4a7
commit
ff4ec31d29
|
@ -313,12 +313,12 @@ public:
|
|||
return MavlinkStreamHeartbeat::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "HEARTBEAT";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_HEARTBEAT;
|
||||
}
|
||||
|
@ -385,12 +385,12 @@ public:
|
|||
return MavlinkStreamStatustext::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "STATUSTEXT";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_STATUSTEXT;
|
||||
}
|
||||
|
@ -450,12 +450,12 @@ public:
|
|||
return MavlinkStreamCommandLong::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "COMMAND_LONG";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_COMMAND_LONG;
|
||||
}
|
||||
|
@ -519,12 +519,12 @@ public:
|
|||
return MavlinkStreamSysStatus::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "SYS_STATUS";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_SYS_STATUS;
|
||||
}
|
||||
|
@ -637,12 +637,12 @@ public:
|
|||
return MavlinkStreamBatteryStatus::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "BATTERY_STATUS";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_BATTERY_STATUS;
|
||||
}
|
||||
|
@ -769,12 +769,12 @@ public:
|
|||
return MavlinkStreamHighresIMU::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "HIGHRES_IMU";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_HIGHRES_IMU;
|
||||
}
|
||||
|
@ -1168,12 +1168,12 @@ public:
|
|||
return MavlinkStreamScaledIMU2::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "SCALED_IMU2";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_SCALED_IMU2;
|
||||
}
|
||||
|
@ -1266,13 +1266,12 @@ public:
|
|||
{
|
||||
return MavlinkStreamScaledIMU3::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "SCALED_IMU3";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_SCALED_IMU3;
|
||||
}
|
||||
|
@ -1367,12 +1366,12 @@ public:
|
|||
return MavlinkStreamAttitude::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "ATTITUDE";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_ATTITUDE;
|
||||
}
|
||||
|
@ -1446,12 +1445,12 @@ public:
|
|||
return MavlinkStreamAttitudeQuaternion::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "ATTITUDE_QUATERNION";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
|
||||
}
|
||||
|
@ -1545,12 +1544,12 @@ public:
|
|||
return MavlinkStreamVFRHUD::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "VFR_HUD";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_VFR_HUD;
|
||||
}
|
||||
|
@ -1674,12 +1673,12 @@ public:
|
|||
return MavlinkStreamGPSRawInt::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "GPS_RAW_INT";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_GPS_RAW_INT;
|
||||
}
|
||||
|
@ -1753,12 +1752,12 @@ public:
|
|||
return MavlinkStreamGPS2Raw::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "GPS2_RAW";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_GPS2_RAW;
|
||||
}
|
||||
|
@ -1829,12 +1828,12 @@ public:
|
|||
return MavlinkStreamSystemTime::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "SYSTEM_TIME";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_SYSTEM_TIME;
|
||||
}
|
||||
|
@ -1892,12 +1891,12 @@ public:
|
|||
return MavlinkStreamTimesync::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "TIMESYNC";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_TIMESYNC;
|
||||
}
|
||||
|
@ -1947,12 +1946,12 @@ public:
|
|||
return MavlinkStreamADSBVehicle::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "ADSB_VEHICLE";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_ADSB_VEHICLE;
|
||||
}
|
||||
|
@ -2044,12 +2043,12 @@ public:
|
|||
return MavlinkStreamUTMGlobalPosition::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "UTM_GLOBAL_POSITION";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_UTM_GLOBAL_POSITION;
|
||||
}
|
||||
|
@ -2233,12 +2232,12 @@ public:
|
|||
return MavlinkStreamCollision::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "COLLISION";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_COLLISION;
|
||||
}
|
||||
|
@ -2304,12 +2303,12 @@ public:
|
|||
return MavlinkStreamCameraTrigger::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "CAMERA_TRIGGER";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_CAMERA_TRIGGER;
|
||||
}
|
||||
|
@ -2412,12 +2411,12 @@ public:
|
|||
return MavlinkStreamCameraImageCaptured::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "CAMERA_IMAGE_CAPTURED";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED;
|
||||
}
|
||||
|
@ -2496,12 +2495,12 @@ public:
|
|||
return MavlinkStreamGlobalPositionInt::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "GLOBAL_POSITION_INT";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
|
||||
}
|
||||
|
@ -2613,12 +2612,12 @@ public:
|
|||
return MavlinkStreamOdometry::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "ODOMETRY";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_ODOMETRY;
|
||||
}
|
||||
|
@ -2748,12 +2747,12 @@ public:
|
|||
return MavlinkStreamLocalPositionNED::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "LOCAL_POSITION_NED";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_LOCAL_POSITION_NED;
|
||||
}
|
||||
|
@ -2819,12 +2818,12 @@ public:
|
|||
return MavlinkStreamEstimatorStatus::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "ESTIMATOR_STATUS";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_VIBRATION;
|
||||
}
|
||||
|
@ -2926,12 +2925,12 @@ public:
|
|||
return MavlinkStreamAttPosMocap::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "ATT_POS_MOCAP";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_ATT_POS_MOCAP;
|
||||
}
|
||||
|
@ -2999,12 +2998,12 @@ public:
|
|||
return MavlinkStreamHomePosition::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "HOME_POSITION";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_HOME_POSITION;
|
||||
}
|
||||
|
@ -3088,7 +3087,7 @@ public:
|
|||
return MavlinkStreamServoOutputRaw<N>::get_name_static();
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
|
||||
}
|
||||
|
@ -3098,7 +3097,7 @@ public:
|
|||
return get_id_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
switch (N) {
|
||||
case 0:
|
||||
|
@ -3179,7 +3178,7 @@ public:
|
|||
return MavlinkStreamActuatorControlTarget<N>::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
switch (N) {
|
||||
case 0:
|
||||
|
@ -3196,7 +3195,7 @@ public:
|
|||
}
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET;
|
||||
}
|
||||
|
@ -3280,12 +3279,12 @@ public:
|
|||
return MavlinkStreamHILActuatorControls::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "HIL_ACTUATOR_CONTROLS";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS;
|
||||
}
|
||||
|
@ -3441,12 +3440,12 @@ public:
|
|||
return MavlinkStreamPositionTargetGlobalInt::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "POSITION_TARGET_GLOBAL_INT";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT;
|
||||
}
|
||||
|
@ -3540,12 +3539,12 @@ public:
|
|||
return MavlinkStreamLocalPositionSetpoint::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "POSITION_TARGET_LOCAL_NED";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED;
|
||||
}
|
||||
|
@ -3618,12 +3617,12 @@ public:
|
|||
return MavlinkStreamAttitudeTarget::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "ATTITUDE_TARGET";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_ATTITUDE_TARGET;
|
||||
}
|
||||
|
@ -3698,12 +3697,12 @@ public:
|
|||
return MavlinkStreamRCChannels::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "RC_CHANNELS";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_RC_CHANNELS;
|
||||
}
|
||||
|
@ -3786,12 +3785,12 @@ public:
|
|||
return MavlinkStreamManualControl::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "MANUAL_CONTROL";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_MANUAL_CONTROL;
|
||||
}
|
||||
|
@ -3863,12 +3862,12 @@ public:
|
|||
return MavlinkStreamTrajectoryRepresentationWaypoints::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "TRAJECTORY_REPRESENTATION_WAYPOINTS";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS;
|
||||
}
|
||||
|
@ -3972,12 +3971,12 @@ public:
|
|||
return MavlinkStreamOpticalFlowRad::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "OPTICAL_FLOW_RAD";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_OPTICAL_FLOW_RAD;
|
||||
}
|
||||
|
@ -4049,12 +4048,12 @@ public:
|
|||
return MavlinkStreamNamedValueFloat::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "NAMED_VALUE_FLOAT";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
|
||||
}
|
||||
|
@ -4118,12 +4117,12 @@ public:
|
|||
return MavlinkStreamDebug::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "DEBUG";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_DEBUG;
|
||||
}
|
||||
|
@ -4185,12 +4184,12 @@ public:
|
|||
return MavlinkStreamDebugVect::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "DEBUG_VECT";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_DEBUG_VECT;
|
||||
}
|
||||
|
@ -4256,12 +4255,12 @@ public:
|
|||
return MavlinkStreamDebugFloatArray::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "DEBUG_FLOAT_ARRAY";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY;
|
||||
}
|
||||
|
@ -4329,12 +4328,12 @@ public:
|
|||
return MavlinkStreamNavControllerOutput::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "NAV_CONTROLLER_OUTPUT";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
|
||||
}
|
||||
|
@ -4410,12 +4409,12 @@ public:
|
|||
return MavlinkStreamCameraCapture::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "CAMERA_CAPTURE";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
@ -4482,12 +4481,12 @@ public:
|
|||
return MavlinkStreamDistanceSensor::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "DISTANCE_SENSOR";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_DISTANCE_SENSOR;
|
||||
}
|
||||
|
@ -4573,12 +4572,12 @@ public:
|
|||
return MavlinkStreamExtendedSysState::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "EXTENDED_SYS_STATE";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_EXTENDED_SYS_STATE;
|
||||
}
|
||||
|
@ -4689,12 +4688,12 @@ public:
|
|||
return MavlinkStreamAltitude::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "ALTITUDE";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_ALTITUDE;
|
||||
}
|
||||
|
@ -4812,12 +4811,12 @@ public:
|
|||
return MavlinkStreamWind::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "WIND_COV";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_WIND_COV;
|
||||
}
|
||||
|
@ -4894,12 +4893,12 @@ public:
|
|||
return MavlinkStreamMountOrientation::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "MOUNT_ORIENTATION";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_MOUNT_ORIENTATION;
|
||||
}
|
||||
|
@ -4966,12 +4965,12 @@ public:
|
|||
return MavlinkStreamGroundTruth::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "GROUND_TRUTH";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_HIL_STATE_QUATERNION;
|
||||
}
|
||||
|
@ -5072,12 +5071,12 @@ public:
|
|||
return MavlinkStreamPing::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "PING";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_PING;
|
||||
}
|
||||
|
@ -5137,12 +5136,12 @@ public:
|
|||
return MavlinkStreamOrbitStatus::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "ORBIT_EXECUTION_STATUS";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS;
|
||||
}
|
||||
|
@ -5206,12 +5205,12 @@ public:
|
|||
return MavlinkStreamObstacleDistance::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
static constexpr const char *get_name_static()
|
||||
{
|
||||
return "OBSTACLE_DISTANCE";
|
||||
}
|
||||
|
||||
static uint16_t get_id_static()
|
||||
static constexpr uint16_t get_id_static()
|
||||
{
|
||||
return MAVLINK_MSG_ID_OBSTACLE_DISTANCE;
|
||||
}
|
||||
|
@ -5274,66 +5273,63 @@ protected:
|
|||
};
|
||||
|
||||
static const StreamListItem streams_list[] = {
|
||||
StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static, &MavlinkStreamHeartbeat::get_id_static),
|
||||
StreamListItem(&MavlinkStreamStatustext::new_instance, &MavlinkStreamStatustext::get_name_static, &MavlinkStreamStatustext::get_id_static),
|
||||
StreamListItem(&MavlinkStreamCommandLong::new_instance, &MavlinkStreamCommandLong::get_name_static, &MavlinkStreamCommandLong::get_id_static),
|
||||
StreamListItem(&MavlinkStreamSysStatus::new_instance, &MavlinkStreamSysStatus::get_name_static, &MavlinkStreamSysStatus::get_id_static),
|
||||
StreamListItem(&MavlinkStreamBatteryStatus::new_instance, &MavlinkStreamBatteryStatus::get_name_static, &MavlinkStreamBatteryStatus::get_id_static),
|
||||
StreamListItem(&MavlinkStreamHighresIMU::new_instance, &MavlinkStreamHighresIMU::get_name_static, &MavlinkStreamHighresIMU::get_id_static),
|
||||
StreamListItem(&MavlinkStreamScaledIMU::new_instance, &MavlinkStreamScaledIMU::get_name_static, &MavlinkStreamScaledIMU::get_id_static),
|
||||
StreamListItem(&MavlinkStreamScaledIMU2::new_instance, &MavlinkStreamScaledIMU2::get_name_static, &MavlinkStreamScaledIMU2::get_id_static),
|
||||
StreamListItem(&MavlinkStreamScaledIMU3::new_instance, &MavlinkStreamScaledIMU3::get_name_static, &MavlinkStreamScaledIMU3::get_id_static),
|
||||
StreamListItem(&MavlinkStreamScaledPressure<0>::new_instance, &MavlinkStreamScaledPressure<0>::get_name_static, &MavlinkStreamScaledPressure<0>::get_id_static),
|
||||
StreamListItem(&MavlinkStreamScaledPressure<1>::new_instance, &MavlinkStreamScaledPressure<1>::get_name_static, &MavlinkStreamScaledPressure<1>::get_id_static),
|
||||
StreamListItem(&MavlinkStreamScaledPressure<2>::new_instance, &MavlinkStreamScaledPressure<2>::get_name_static, &MavlinkStreamScaledPressure<2>::get_id_static),
|
||||
StreamListItem(&MavlinkStreamAttitude::new_instance, &MavlinkStreamAttitude::get_name_static, &MavlinkStreamAttitude::get_id_static),
|
||||
StreamListItem(&MavlinkStreamAttitudeQuaternion::new_instance, &MavlinkStreamAttitudeQuaternion::get_name_static, &MavlinkStreamAttitudeQuaternion::get_id_static),
|
||||
StreamListItem(&MavlinkStreamVFRHUD::new_instance, &MavlinkStreamVFRHUD::get_name_static, &MavlinkStreamVFRHUD::get_id_static),
|
||||
StreamListItem(&MavlinkStreamGPSRawInt::new_instance, &MavlinkStreamGPSRawInt::get_name_static, &MavlinkStreamGPSRawInt::get_id_static),
|
||||
StreamListItem(&MavlinkStreamGPS2Raw::new_instance, &MavlinkStreamGPS2Raw::get_name_static, &MavlinkStreamGPS2Raw::get_id_static),
|
||||
StreamListItem(&MavlinkStreamSystemTime::new_instance, &MavlinkStreamSystemTime::get_name_static, &MavlinkStreamSystemTime::get_id_static),
|
||||
StreamListItem(&MavlinkStreamTimesync::new_instance, &MavlinkStreamTimesync::get_name_static, &MavlinkStreamTimesync::get_id_static),
|
||||
StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static, &MavlinkStreamGlobalPositionInt::get_id_static),
|
||||
StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static, &MavlinkStreamLocalPositionNED::get_id_static),
|
||||
StreamListItem(&MavlinkStreamOdometry::new_instance, &MavlinkStreamOdometry::get_name_static, &MavlinkStreamOdometry::get_id_static),
|
||||
StreamListItem(&MavlinkStreamEstimatorStatus::new_instance, &MavlinkStreamEstimatorStatus::get_name_static, &MavlinkStreamEstimatorStatus::get_id_static),
|
||||
StreamListItem(&MavlinkStreamAttPosMocap::new_instance, &MavlinkStreamAttPosMocap::get_name_static, &MavlinkStreamAttPosMocap::get_id_static),
|
||||
StreamListItem(&MavlinkStreamHomePosition::new_instance, &MavlinkStreamHomePosition::get_name_static, &MavlinkStreamHomePosition::get_id_static),
|
||||
StreamListItem(&MavlinkStreamServoOutputRaw<0>::new_instance, &MavlinkStreamServoOutputRaw<0>::get_name_static, &MavlinkStreamServoOutputRaw<0>::get_id_static),
|
||||
StreamListItem(&MavlinkStreamServoOutputRaw<1>::new_instance, &MavlinkStreamServoOutputRaw<1>::get_name_static, &MavlinkStreamServoOutputRaw<1>::get_id_static),
|
||||
StreamListItem(&MavlinkStreamHILActuatorControls::new_instance, &MavlinkStreamHILActuatorControls::get_name_static, &MavlinkStreamHILActuatorControls::get_id_static),
|
||||
StreamListItem(&MavlinkStreamPositionTargetGlobalInt::new_instance, &MavlinkStreamPositionTargetGlobalInt::get_name_static, &MavlinkStreamPositionTargetGlobalInt::get_id_static),
|
||||
StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static, &MavlinkStreamLocalPositionSetpoint::get_id_static),
|
||||
StreamListItem(&MavlinkStreamAttitudeTarget::new_instance, &MavlinkStreamAttitudeTarget::get_name_static, &MavlinkStreamAttitudeTarget::get_id_static),
|
||||
StreamListItem(&MavlinkStreamRCChannels::new_instance, &MavlinkStreamRCChannels::get_name_static, &MavlinkStreamRCChannels::get_id_static),
|
||||
StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static, &MavlinkStreamManualControl::get_id_static),
|
||||
StreamListItem(&MavlinkStreamTrajectoryRepresentationWaypoints::new_instance, &MavlinkStreamTrajectoryRepresentationWaypoints::get_name_static, &MavlinkStreamTrajectoryRepresentationWaypoints::get_id_static),
|
||||
StreamListItem(&MavlinkStreamOpticalFlowRad::new_instance, &MavlinkStreamOpticalFlowRad::get_name_static, &MavlinkStreamOpticalFlowRad::get_id_static),
|
||||
StreamListItem(&MavlinkStreamActuatorControlTarget<0>::new_instance, &MavlinkStreamActuatorControlTarget<0>::get_name_static, &MavlinkStreamActuatorControlTarget<0>::get_id_static),
|
||||
//StreamListItem(&MavlinkStreamActuatorControlTarget<1>::new_instance, &MavlinkStreamActuatorControlTarget<1>::get_name_static, &MavlinkStreamActuatorControlTarget<1>::get_id_static),
|
||||
//StreamListItem(&MavlinkStreamActuatorControlTarget<2>::new_instance, &MavlinkStreamActuatorControlTarget<2>::get_name_static, &MavlinkStreamActuatorControlTarget<2>::get_id_static),
|
||||
//StreamListItem(&MavlinkStreamActuatorControlTarget<3>::new_instance, &MavlinkStreamActuatorControlTarget<3>::get_name_static, &MavlinkStreamActuatorControlTarget<3>::get_id_static),
|
||||
StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static, &MavlinkStreamNamedValueFloat::get_id_static),
|
||||
StreamListItem(&MavlinkStreamDebug::new_instance, &MavlinkStreamDebug::get_name_static, &MavlinkStreamDebug::get_id_static),
|
||||
StreamListItem(&MavlinkStreamDebugVect::new_instance, &MavlinkStreamDebugVect::get_name_static, &MavlinkStreamDebugVect::get_id_static),
|
||||
StreamListItem(&MavlinkStreamDebugFloatArray::new_instance, &MavlinkStreamDebugFloatArray::get_name_static, &MavlinkStreamDebugFloatArray::get_id_static),
|
||||
StreamListItem(&MavlinkStreamNavControllerOutput::new_instance, &MavlinkStreamNavControllerOutput::get_name_static, &MavlinkStreamNavControllerOutput::get_id_static),
|
||||
StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static, &MavlinkStreamCameraCapture::get_id_static),
|
||||
StreamListItem(&MavlinkStreamCameraTrigger::new_instance, &MavlinkStreamCameraTrigger::get_name_static, &MavlinkStreamCameraTrigger::get_id_static),
|
||||
StreamListItem(&MavlinkStreamCameraImageCaptured::new_instance, &MavlinkStreamCameraImageCaptured::get_name_static, &MavlinkStreamCameraImageCaptured::get_id_static),
|
||||
StreamListItem(&MavlinkStreamDistanceSensor::new_instance, &MavlinkStreamDistanceSensor::get_name_static, &MavlinkStreamDistanceSensor::get_id_static),
|
||||
StreamListItem(&MavlinkStreamExtendedSysState::new_instance, &MavlinkStreamExtendedSysState::get_name_static, &MavlinkStreamExtendedSysState::get_id_static),
|
||||
StreamListItem(&MavlinkStreamAltitude::new_instance, &MavlinkStreamAltitude::get_name_static, &MavlinkStreamAltitude::get_id_static),
|
||||
StreamListItem(&MavlinkStreamADSBVehicle::new_instance, &MavlinkStreamADSBVehicle::get_name_static, &MavlinkStreamADSBVehicle::get_id_static),
|
||||
StreamListItem(&MavlinkStreamUTMGlobalPosition::new_instance, &MavlinkStreamUTMGlobalPosition::get_name_static, &MavlinkStreamUTMGlobalPosition::get_id_static),
|
||||
StreamListItem(&MavlinkStreamCollision::new_instance, &MavlinkStreamCollision::get_name_static, &MavlinkStreamCollision::get_id_static),
|
||||
StreamListItem(&MavlinkStreamWind::new_instance, &MavlinkStreamWind::get_name_static, &MavlinkStreamWind::get_id_static),
|
||||
StreamListItem(&MavlinkStreamMountOrientation::new_instance, &MavlinkStreamMountOrientation::get_name_static, &MavlinkStreamMountOrientation::get_id_static),
|
||||
StreamListItem(&MavlinkStreamHighLatency2::new_instance, &MavlinkStreamHighLatency2::get_name_static, &MavlinkStreamHighLatency2::get_id_static),
|
||||
StreamListItem(&MavlinkStreamGroundTruth::new_instance, &MavlinkStreamGroundTruth::get_name_static, &MavlinkStreamGroundTruth::get_id_static),
|
||||
StreamListItem(&MavlinkStreamPing::new_instance, &MavlinkStreamPing::get_name_static, &MavlinkStreamPing::get_id_static),
|
||||
StreamListItem(&MavlinkStreamOrbitStatus::new_instance, &MavlinkStreamOrbitStatus::get_name_static, &MavlinkStreamOrbitStatus::get_id_static),
|
||||
StreamListItem(&MavlinkStreamObstacleDistance::new_instance, &MavlinkStreamObstacleDistance::get_name_static, &MavlinkStreamObstacleDistance::get_id_static)
|
||||
create_stream_list_item<MavlinkStreamHeartbeat>(),
|
||||
create_stream_list_item<MavlinkStreamStatustext>(),
|
||||
create_stream_list_item<MavlinkStreamCommandLong>(),
|
||||
create_stream_list_item<MavlinkStreamSysStatus>(),
|
||||
create_stream_list_item<MavlinkStreamBatteryStatus>(),
|
||||
create_stream_list_item<MavlinkStreamHighresIMU>(),
|
||||
create_stream_list_item<MavlinkStreamScaledIMU>(),
|
||||
create_stream_list_item<MavlinkStreamScaledIMU2>(),
|
||||
create_stream_list_item<MavlinkStreamScaledIMU3>(),
|
||||
create_stream_list_item<MavlinkStreamScaledPressure<0> >(),
|
||||
// create_stream_list_item<MavlinkStreamScaledPressure<1> >(),
|
||||
// create_stream_list_item<MavlinkStreamScaledPressure<2> >(),
|
||||
create_stream_list_item<MavlinkStreamAttitude>(),
|
||||
create_stream_list_item<MavlinkStreamAttitudeQuaternion>(),
|
||||
create_stream_list_item<MavlinkStreamVFRHUD>(),
|
||||
create_stream_list_item<MavlinkStreamGPSRawInt>(),
|
||||
create_stream_list_item<MavlinkStreamGPS2Raw>(),
|
||||
create_stream_list_item<MavlinkStreamSystemTime>(),
|
||||
create_stream_list_item<MavlinkStreamTimesync>(),
|
||||
create_stream_list_item<MavlinkStreamGlobalPositionInt>(),
|
||||
create_stream_list_item<MavlinkStreamLocalPositionNED>(),
|
||||
create_stream_list_item<MavlinkStreamOdometry>(),
|
||||
create_stream_list_item<MavlinkStreamEstimatorStatus>(),
|
||||
create_stream_list_item<MavlinkStreamAttPosMocap>(),
|
||||
create_stream_list_item<MavlinkStreamHomePosition>(),
|
||||
create_stream_list_item<MavlinkStreamServoOutputRaw<0> >(),
|
||||
create_stream_list_item<MavlinkStreamServoOutputRaw<1> >(),
|
||||
create_stream_list_item<MavlinkStreamHILActuatorControls>(),
|
||||
create_stream_list_item<MavlinkStreamPositionTargetGlobalInt>(),
|
||||
create_stream_list_item<MavlinkStreamLocalPositionSetpoint>(),
|
||||
create_stream_list_item<MavlinkStreamAttitudeTarget>(),
|
||||
create_stream_list_item<MavlinkStreamRCChannels>(),
|
||||
create_stream_list_item<MavlinkStreamManualControl>(),
|
||||
create_stream_list_item<MavlinkStreamTrajectoryRepresentationWaypoints>(),
|
||||
create_stream_list_item<MavlinkStreamOpticalFlowRad>(),
|
||||
create_stream_list_item<MavlinkStreamActuatorControlTarget<0> >(),
|
||||
create_stream_list_item<MavlinkStreamNamedValueFloat>(),
|
||||
create_stream_list_item<MavlinkStreamDebug>(),
|
||||
create_stream_list_item<MavlinkStreamDebugVect>(),
|
||||
create_stream_list_item<MavlinkStreamDebugFloatArray>(),
|
||||
create_stream_list_item<MavlinkStreamNavControllerOutput>(),
|
||||
create_stream_list_item<MavlinkStreamCameraCapture>(),
|
||||
create_stream_list_item<MavlinkStreamCameraTrigger>(),
|
||||
create_stream_list_item<MavlinkStreamCameraImageCaptured>(),
|
||||
create_stream_list_item<MavlinkStreamDistanceSensor>(),
|
||||
create_stream_list_item<MavlinkStreamExtendedSysState>(),
|
||||
create_stream_list_item<MavlinkStreamAltitude>(),
|
||||
create_stream_list_item<MavlinkStreamADSBVehicle>(),
|
||||
create_stream_list_item<MavlinkStreamUTMGlobalPosition>(),
|
||||
create_stream_list_item<MavlinkStreamCollision>(),
|
||||
create_stream_list_item<MavlinkStreamWind>(),
|
||||
create_stream_list_item<MavlinkStreamMountOrientation>(),
|
||||
create_stream_list_item<MavlinkStreamHighLatency2>(),
|
||||
create_stream_list_item<MavlinkStreamGroundTruth>(),
|
||||
create_stream_list_item<MavlinkStreamPing>(),
|
||||
create_stream_list_item<MavlinkStreamOrbitStatus>(),
|
||||
create_stream_list_item<MavlinkStreamObstacleDistance>()
|
||||
};
|
||||
|
||||
const char *get_stream_name(const uint16_t msg_id)
|
||||
|
|
|
@ -48,16 +48,24 @@ class StreamListItem
|
|||
|
||||
public:
|
||||
MavlinkStream *(*new_instance)(Mavlink *mavlink);
|
||||
const char *(*get_name)();
|
||||
uint16_t (*get_id)();
|
||||
const char *name;
|
||||
uint16_t id;
|
||||
|
||||
StreamListItem(MavlinkStream * (*inst)(Mavlink *mavlink), const char *(*name)(), uint16_t (*id)()) :
|
||||
StreamListItem(MavlinkStream * (*inst)(Mavlink *mavlink), const char *_name, uint16_t _id) :
|
||||
new_instance(inst),
|
||||
get_name(name),
|
||||
get_id(id) {}
|
||||
name(_name),
|
||||
id(_id) {}
|
||||
|
||||
const char *get_name() const { return name; }
|
||||
uint16_t get_id() const { return id; }
|
||||
};
|
||||
|
||||
template <class T>
|
||||
static StreamListItem create_stream_list_item()
|
||||
{
|
||||
return StreamListItem(&T::new_instance, T::get_name_static(), T::get_id_static());
|
||||
}
|
||||
|
||||
const char *get_stream_name(const uint16_t msg_id);
|
||||
MavlinkStream *create_mavlink_stream(const char *stream_name, Mavlink *mavlink);
|
||||
|
||||
|
|
Loading…
Reference in New Issue