mirror of https://github.com/ArduPilot/ardupilot
AP_PiccoloCAN: fix compilation when HAL_WITH_ESC_TELEM == 0
This commit is contained in:
parent
f4409066bc
commit
d15042d7c0
|
@ -352,6 +352,9 @@ void AP_PiccoloCAN::send_esc_messages(void)
|
|||
// interpret an ESC message received over CAN
|
||||
bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame)
|
||||
{
|
||||
bool result = true;
|
||||
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
uint64_t timestamp = AP_HAL::micros64();
|
||||
|
||||
// The ESC address is the lower byte of the address
|
||||
|
@ -372,8 +375,6 @@ bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame)
|
|||
|
||||
PiccoloESC_Info_t &esc = _esc_info[addr];
|
||||
|
||||
bool result = true;
|
||||
|
||||
/*
|
||||
* The STATUS_A packet has slight variations between Gen-1 and Gen-2 ESCs.
|
||||
* We can differentiate between the different versions,
|
||||
|
@ -445,6 +446,7 @@ bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame)
|
|||
// Reset the Rx timestamp
|
||||
esc.last_rx_msg_timestamp = timestamp;
|
||||
}
|
||||
#endif // HAL_WITH_ESC_TELEM
|
||||
|
||||
return result;
|
||||
}
|
||||
|
|
|
@ -19,7 +19,6 @@
|
|||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_CANManager/AP_CANDriver.h>
|
||||
#include <AP_HAL/Semaphores.h>
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_ESC_Telem/AP_ESC_Telem_Backend.h>
|
||||
|
@ -114,7 +113,6 @@ private:
|
|||
uint8_t _driver_index;
|
||||
AP_HAL::CANIface* _can_iface;
|
||||
HAL_EventHandle _event_handle;
|
||||
HAL_Semaphore _telem_sem;
|
||||
|
||||
struct PiccoloESC_Info_t {
|
||||
|
||||
|
|
Loading…
Reference in New Issue