Copter: move to using CANManager library

This commit is contained in:
Siddharth Purohit 2020-05-31 17:17:48 +05:30 committed by Andrew Tridgell
parent ddfd186618
commit 9b9954aa46
4 changed files with 9 additions and 9 deletions

View File

@ -1,6 +1,6 @@
#include "Copter.h" #include "Copter.h"
#if HAL_WITH_UAVCAN #if HAL_MAX_CAN_PROTOCOL_DRIVERS
#include <AP_ToshibaCAN/AP_ToshibaCAN.h> #include <AP_ToshibaCAN/AP_ToshibaCAN.h>
#endif #endif
@ -312,12 +312,12 @@ bool AP_Arming_Copter::motor_checks(bool display_failure)
} }
// if this is a multicopter using ToshibaCAN ESCs ensure MOT_PMW_MIN = 1000, MOT_PWM_MAX = 2000 // if this is a multicopter using ToshibaCAN ESCs ensure MOT_PMW_MIN = 1000, MOT_PWM_MAX = 2000
#if HAL_WITH_UAVCAN && (FRAME_CONFIG != HELI_FRAME) #if HAL_MAX_CAN_PROTOCOL_DRIVERS && (FRAME_CONFIG != HELI_FRAME)
bool tcan_active = false; bool tcan_active = false;
uint8_t tcan_index = 0; uint8_t tcan_index = 0;
const uint8_t num_drivers = AP::can().get_num_drivers(); const 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++) {
if (AP::can().get_protocol_type(i) == AP_BoardConfig_CAN::Protocol_Type_ToshibaCAN) { if (AP::can().get_driver_type(i) == AP_CANManager::Driver_Type_ToshibaCAN) {
tcan_active = true; tcan_active = true;
tcan_index = i; tcan_index = i;
} }

View File

@ -566,10 +566,10 @@ const AP_Param::Info Copter::var_info[] = {
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp // @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig), GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
#if HAL_WITH_UAVCAN #if HAL_MAX_CAN_PROTOCOL_DRIVERS
// @Group: CAN_ // @Group: CAN_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp // @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
GOBJECT(BoardConfig_CAN, "CAN_", AP_BoardConfig_CAN), GOBJECT(can_mgr, "CAN_", AP_CANManager),
#endif #endif
#if SPRAYER_ENABLED == ENABLED #if SPRAYER_ENABLED == ENABLED

View File

@ -54,7 +54,7 @@ public:
k_param_NavEKF2, k_param_NavEKF2,
k_param_g2, // 2nd block of parameters k_param_g2, // 2nd block of parameters
k_param_NavEKF3, k_param_NavEKF3,
k_param_BoardConfig_CAN, k_param_can_mgr,
k_param_osd, k_param_osd,
// simulation // simulation

View File

@ -22,8 +22,8 @@ void Copter::init_ardupilot()
#endif #endif
BoardConfig.init(); BoardConfig.init();
#if HAL_WITH_UAVCAN #if HAL_MAX_CAN_PROTOCOL_DRIVERS
BoardConfig_CAN.init(); can_mgr.init();
#endif #endif
// init cargo gripper // init cargo gripper