GCS_MAVLink: send ESC telemetry messages

This commit is contained in:
Andrew Tridgell 2018-05-31 07:35:56 +10:00
parent dc9ae42067
commit 4e4e5a2feb
2 changed files with 13 additions and 0 deletions

View File

@ -81,6 +81,7 @@ enum ap_message : uint8_t {
MSG_BATTERY_STATUS,
MSG_AOA_SSA,
MSG_LANDING,
MSG_ESC_TELEMETRY,
MSG_NAMED_FLOAT,
MSG_LAST // MSG_LAST must be the last entry in this enum
};

View File

@ -21,6 +21,7 @@
#include <AP_RangeFinder/RangeFinder_Backend.h>
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Gripper/AP_Gripper.h>
#include <AP_BLHeli/AP_BLHeli.h>
#include "GCS.h"
@ -2985,6 +2986,17 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
send_vibration();
break;
#ifdef HAVE_AP_BLHELI_SUPPORT
case MSG_ESC_TELEMETRY: {
CHECK_PAYLOAD_SIZE(ESC_TELEMETRY_1_TO_4);
AP_BLHeli *blheli = AP_BLHeli::get_instance();
if (blheli) {
blheli->send_esc_telemetry_mavlink(uint8_t(chan));
}
break;
}
#endif
default:
// try_send_message must always at some stage return true for
// a message, or we will attempt to infinitely retry the