SRV_Channels: use AP_CANManager library

This commit is contained in:
Siddharth Purohit 2020-05-31 18:22:33 +05:30 committed by Andrew Tridgell
parent 42f5f986d8
commit 8b74f94a7a

View File

@ -22,8 +22,8 @@
#include <AP_Vehicle/AP_Vehicle.h> #include <AP_Vehicle/AP_Vehicle.h>
#include "SRV_Channel.h" #include "SRV_Channel.h"
#if HAL_WITH_UAVCAN #if HAL_MAX_CAN_PROTOCOL_DRIVERS
#include <AP_BoardConfig/AP_BoardConfig_CAN.h> #include <AP_CANManager/AP_CANManager.h>
#include <AP_UAVCAN/AP_UAVCAN.h> #include <AP_UAVCAN/AP_UAVCAN.h>
// To be replaced with macro saying if KDECAN library is included // To be replaced with macro saying if KDECAN library is included
@ -278,12 +278,12 @@ void SRV_Channels::push()
blheli_ptr->update_telemetry(); blheli_ptr->update_telemetry();
#endif #endif
#if HAL_WITH_UAVCAN #if HAL_MAX_CAN_PROTOCOL_DRIVERS
// push outputs to CAN // push outputs to CAN
uint8_t can_num_drivers = AP::can().get_num_drivers(); uint8_t can_num_drivers = AP::can().get_num_drivers();
for (uint8_t i = 0; i < can_num_drivers; i++) { for (uint8_t i = 0; i < can_num_drivers; i++) {
switch (AP::can().get_protocol_type(i)) { switch (AP::can().get_driver_type(i)) {
case AP_BoardConfig_CAN::Protocol_Type_UAVCAN: { case AP_CANManager::Driver_Type_UAVCAN: {
AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i); AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i);
if (ap_uavcan == nullptr) { if (ap_uavcan == nullptr) {
continue; continue;
@ -291,7 +291,7 @@ void SRV_Channels::push()
ap_uavcan->SRV_push_servos(); ap_uavcan->SRV_push_servos();
break; break;
} }
case AP_BoardConfig_CAN::Protocol_Type_KDECAN: { case AP_CANManager::Driver_Type_KDECAN: {
// To be replaced with macro saying if KDECAN library is included // 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) #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); AP_KDECAN *ap_kdecan = AP_KDECAN::get_kdecan(i);
@ -302,7 +302,7 @@ void SRV_Channels::push()
#endif #endif
break; break;
} }
case AP_BoardConfig_CAN::Protocol_Type_ToshibaCAN: { case AP_CANManager::Driver_Type_ToshibaCAN: {
AP_ToshibaCAN *ap_tcan = AP_ToshibaCAN::get_tcan(i); AP_ToshibaCAN *ap_tcan = AP_ToshibaCAN::get_tcan(i);
if (ap_tcan == nullptr) { if (ap_tcan == nullptr) {
continue; continue;
@ -311,7 +311,7 @@ void SRV_Channels::push()
break; break;
} }
#if HAL_PICCOLO_CAN_ENABLE #if HAL_PICCOLO_CAN_ENABLE
case AP_BoardConfig_CAN::Protocol_Type_PiccoloCAN: { case AP_CANManager::Driver_Type_PiccoloCAN: {
AP_PiccoloCAN *ap_pcan = AP_PiccoloCAN::get_pcan(i); AP_PiccoloCAN *ap_pcan = AP_PiccoloCAN::get_pcan(i);
if (ap_pcan == nullptr) { if (ap_pcan == nullptr) {
continue; continue;
@ -320,10 +320,11 @@ void SRV_Channels::push()
break; break;
} }
#endif #endif
case AP_BoardConfig_CAN::Protocol_Type_None: case AP_CANManager::Driver_Type_CANTester:
case AP_CANManager::Driver_Type_None:
default: default:
break; break;
} }
} }
#endif // HAL_WITH_UAVCAN #endif // HAL_NUM_CAN_IFACES
} }