mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: use generic send_esc_telemetry_mavlink() from AP_ESC_Telem
This commit is contained in:
parent
e19bf8149b
commit
fca6925129
@ -5058,60 +5058,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||||||
send_autopilot_version();
|
send_autopilot_version();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_ESC_TELEMETRY: {
|
case MSG_ESC_TELEMETRY:
|
||||||
#ifdef HAVE_AP_BLHELI_SUPPORT
|
#if HAL_WITH_ESC_TELEM
|
||||||
CHECK_PAYLOAD_SIZE(ESC_TELEMETRY_1_TO_4);
|
AP::esc_telem().send_esc_telemetry_mavlink(uint8_t(chan));
|
||||||
AP_BLHeli *blheli = AP_BLHeli::get_singleton();
|
|
||||||
if (blheli) {
|
|
||||||
blheli->send_esc_telemetry_mavlink(uint8_t(chan));
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
|
||||||
uint8_t num_drivers = AP::can().get_num_drivers();
|
|
||||||
|
|
||||||
for (uint8_t i = 0; i < num_drivers; i++) {
|
|
||||||
switch (AP::can().get_driver_type(i)) {
|
|
||||||
case AP_CANManager::Driver_Type_KDECAN: {
|
|
||||||
// To be replaced with macro saying if KDECAN library is included
|
|
||||||
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
|
|
||||||
AP_KDECAN *ap_kdecan = AP_KDECAN::get_kdecan(i);
|
|
||||||
if (ap_kdecan != nullptr) {
|
|
||||||
ap_kdecan->send_mavlink(uint8_t(chan));
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case AP_CANManager::Driver_Type_ToshibaCAN: {
|
|
||||||
AP_ToshibaCAN *ap_tcan = AP_ToshibaCAN::get_tcan(i);
|
|
||||||
if (ap_tcan != nullptr) {
|
|
||||||
ap_tcan->send_esc_telemetry_mavlink(uint8_t(chan));
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
#if HAL_PICCOLO_CAN_ENABLE
|
|
||||||
case AP_CANManager::Driver_Type_PiccoloCAN: {
|
|
||||||
AP_PiccoloCAN *ap_pcan = AP_PiccoloCAN::get_pcan(i);
|
|
||||||
if (ap_pcan != nullptr) {
|
|
||||||
ap_pcan->send_esc_telemetry_mavlink(uint8_t(chan));
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
case AP_CANManager::Driver_Type_UAVCAN: {
|
|
||||||
AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i);
|
|
||||||
if (ap_uavcan != nullptr) {
|
|
||||||
ap_uavcan->send_esc_telemetry_mavlink(uint8_t(chan));
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case AP_CANManager::Driver_Type_None:
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
}
|
|
||||||
|
|
||||||
case MSG_EFI_STATUS: {
|
case MSG_EFI_STATUS: {
|
||||||
#if EFI_ENABLED
|
#if EFI_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user