mirror of https://github.com/ArduPilot/ardupilot
AP_ESC_Telem: move to using CANManager library
This commit is contained in:
parent
bf1a7799f8
commit
e9430d7f80
|
@ -16,8 +16,8 @@
|
|||
#include "AP_ESC_Telem.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_WITH_UAVCAN
|
||||
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
|
||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||
#include <AP_CANManager/AP_CANManager.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <AP_UAVCAN/AP_UAVCAN.h>
|
||||
|
@ -38,10 +38,10 @@ AP_ESC_Telem::AP_ESC_Telem()
|
|||
// get an individual ESC's usage time in seconds if available, returns true on success
|
||||
bool AP_ESC_Telem::get_usage_seconds(uint8_t esc_id, uint32_t& usage_sec) const
|
||||
{
|
||||
#if HAL_WITH_UAVCAN
|
||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||
const uint8_t num_drivers = AP::can().get_num_drivers();
|
||||
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) {
|
||||
AP_ToshibaCAN *tcan = AP_ToshibaCAN::get_tcan(i);
|
||||
if (tcan != nullptr) {
|
||||
usage_sec = tcan->get_usage_seconds(esc_id);
|
||||
|
|
Loading…
Reference in New Issue