Browse Source

AP_Arming: move to using CANManager library

zr-v5.1
Siddharth Purohit 5 years ago committed by Andrew Tridgell
parent
commit
0fa6e2bbcc
  1. 23
      libraries/AP_Arming/AP_Arming.cpp

23
libraries/AP_Arming/AP_Arming.cpp

@ -39,8 +39,8 @@
#include <AP_RCMapper/AP_RCMapper.h> #include <AP_RCMapper/AP_RCMapper.h>
#include <AP_VisualOdom/AP_VisualOdom.h> #include <AP_VisualOdom/AP_VisualOdom.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_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Vehicle/AP_Vehicle.h> #include <AP_Vehicle/AP_Vehicle.h>
@ -836,14 +836,14 @@ bool AP_Arming::proximity_checks(bool report) const
bool AP_Arming::can_checks(bool report) bool AP_Arming::can_checks(bool report)
{ {
#if HAL_WITH_UAVCAN #if HAL_MAX_CAN_PROTOCOL_DRIVERS
if (check_enabled(ARMING_CHECK_SYSTEM)) { if (check_enabled(ARMING_CHECK_SYSTEM)) {
char fail_msg[50] = {}; char fail_msg[50] = {};
uint8_t num_drivers = AP::can().get_num_drivers(); uint8_t num_drivers = AP::can().get_num_drivers();
for (uint8_t i = 0; i < num_drivers; i++) { for (uint8_t i = 0; i < num_drivers; i++) {
switch (AP::can().get_protocol_type(i)) { switch (AP::can().get_driver_type(i)) {
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);
@ -854,7 +854,7 @@ bool AP_Arming::can_checks(bool report)
#endif #endif
break; break;
} }
case AP_BoardConfig_CAN::Protocol_Type_PiccoloCAN: { case AP_CANManager::Driver_Type_PiccoloCAN: {
#if HAL_PICCOLO_CAN_ENABLE #if HAL_PICCOLO_CAN_ENABLE
AP_PiccoloCAN *ap_pcan = AP_PiccoloCAN::get_pcan(i); AP_PiccoloCAN *ap_pcan = AP_PiccoloCAN::get_pcan(i);
@ -869,7 +869,7 @@ bool AP_Arming::can_checks(bool report)
#endif #endif
break; break;
} }
case AP_BoardConfig_CAN::Protocol_Type_UAVCAN: case AP_CANManager::Driver_Type_UAVCAN:
{ {
if (!AP::uavcan_dna_server().prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) { if (!AP::uavcan_dna_server().prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
check_failed(ARMING_CHECK_SYSTEM, report, "UAVCAN: %s", fail_msg); check_failed(ARMING_CHECK_SYSTEM, report, "UAVCAN: %s", fail_msg);
@ -877,14 +877,19 @@ bool AP_Arming::can_checks(bool report)
} }
break; break;
} }
case AP_BoardConfig_CAN::Protocol_Type_ToshibaCAN: case AP_CANManager::Driver_Type_ToshibaCAN:
{ {
// toshibacan doesn't currently have any prearm // toshibacan doesn't currently have any prearm
// checks. Theres scope for adding a "not // checks. Theres scope for adding a "not
// initialised" prearm check. // initialised" prearm check.
break; break;
} }
case AP_BoardConfig_CAN::Protocol_Type_None: case AP_CANManager::Driver_Type_CANTester:
{
check_failed(ARMING_CHECK_SYSTEM, report, "TestCAN: No Arming with TestCAN enabled");
break;
}
case AP_CANManager::Driver_Type_None:
break; break;
} }
} }

Loading…
Cancel
Save