mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
8328368164
* remove unnecessary nullptr check, these are always called from an initialized AP_DroneCAN so if it's nullptr something has gone horrifically wrong * pass in driver index instead of repeatedly calling function to get it * simplify error handling; knowing exactly which allocation failed is not super helpful and one failing likely means subsequent ones will too, as it can only fail due to being out of memory
27 lines
684 B
C++
27 lines
684 B
C++
#pragma once
|
|
|
|
#include "AP_EFI_config.h"
|
|
|
|
#if AP_EFI_DRONECAN_ENABLED
|
|
#include "AP_EFI.h"
|
|
#include "AP_EFI_Backend.h"
|
|
#include <AP_DroneCAN/AP_DroneCAN.h>
|
|
|
|
class AP_EFI_DroneCAN : public AP_EFI_Backend {
|
|
public:
|
|
AP_EFI_DroneCAN(AP_EFI &_frontend);
|
|
|
|
void update() override;
|
|
|
|
static bool subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
|
static void trampoline_status(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ice_reciprocating_Status &msg);
|
|
|
|
private:
|
|
void handle_status(const uavcan_equipment_ice_reciprocating_Status &pkt);
|
|
|
|
// singleton for trampoline
|
|
static AP_EFI_DroneCAN *driver;
|
|
};
|
|
#endif // AP_EFI_DRONECAN_ENABLED
|
|
|