mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Blimp: do not send MSG_RPM if RPM not enabled
This commit is contained in:
parent
659ea9e08b
commit
51d176338c
@ -1,6 +1,7 @@
|
|||||||
#include "Blimp.h"
|
#include "Blimp.h"
|
||||||
|
|
||||||
#include "GCS_Mavlink.h"
|
#include "GCS_Mavlink.h"
|
||||||
|
#include <AP_RPM/AP_RPM_config.h>
|
||||||
|
|
||||||
MAV_TYPE GCS_Blimp::frame_type() const
|
MAV_TYPE GCS_Blimp::frame_type() const
|
||||||
{
|
{
|
||||||
@ -358,7 +359,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
|||||||
MSG_MAG_CAL_PROGRESS,
|
MSG_MAG_CAL_PROGRESS,
|
||||||
MSG_EKF_STATUS_REPORT,
|
MSG_EKF_STATUS_REPORT,
|
||||||
MSG_VIBRATION,
|
MSG_VIBRATION,
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
MSG_RPM,
|
MSG_RPM,
|
||||||
|
#endif
|
||||||
MSG_ESC_TELEMETRY,
|
MSG_ESC_TELEMETRY,
|
||||||
MSG_GENERATOR_STATUS,
|
MSG_GENERATOR_STATUS,
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user