mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_HAL: support of several CAN managers (virtual drivers)
This commit is contained in:
parent
7314b515c0
commit
8f2306fd19
@ -29,6 +29,9 @@
|
|||||||
#include <uavcan/driver/can.hpp>
|
#include <uavcan/driver/can.hpp>
|
||||||
#include <uavcan/time.hpp>
|
#include <uavcan/time.hpp>
|
||||||
|
|
||||||
|
#define MAX_NUMBER_OF_CAN_INTERFACES 2
|
||||||
|
#define MAX_NUMBER_OF_CAN_DRIVERS 2
|
||||||
|
|
||||||
class AP_UAVCAN;
|
class AP_UAVCAN;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -108,6 +111,7 @@ public:
|
|||||||
true - CAN manager is initialized
|
true - CAN manager is initialized
|
||||||
*/
|
*/
|
||||||
virtual bool is_initialized() = 0;
|
virtual bool is_initialized() = 0;
|
||||||
|
virtual void initialized(bool val);
|
||||||
|
|
||||||
virtual AP_UAVCAN *get_UAVCAN(void);
|
virtual AP_UAVCAN *get_UAVCAN(void);
|
||||||
virtual void set_UAVCAN(AP_UAVCAN *uavcan);
|
virtual void set_UAVCAN(AP_UAVCAN *uavcan);
|
||||||
|
@ -34,7 +34,11 @@ public:
|
|||||||
AP_HAL::Scheduler* _scheduler,
|
AP_HAL::Scheduler* _scheduler,
|
||||||
AP_HAL::Util* _util,
|
AP_HAL::Util* _util,
|
||||||
AP_HAL::OpticalFlow *_opticalflow,
|
AP_HAL::OpticalFlow *_opticalflow,
|
||||||
AP_HAL::CANManager* _can_mgr)
|
#if HAL_WITH_UAVCAN
|
||||||
|
AP_HAL::CANManager* _can_mgr[MAX_NUMBER_OF_CAN_DRIVERS])
|
||||||
|
#else
|
||||||
|
AP_HAL::CANManager** _can_mgr)
|
||||||
|
#endif
|
||||||
:
|
:
|
||||||
uartA(_uartA),
|
uartA(_uartA),
|
||||||
uartB(_uartB),
|
uartB(_uartB),
|
||||||
@ -52,9 +56,18 @@ public:
|
|||||||
rcout(_rcout),
|
rcout(_rcout),
|
||||||
scheduler(_scheduler),
|
scheduler(_scheduler),
|
||||||
util(_util),
|
util(_util),
|
||||||
opticalflow(_opticalflow),
|
opticalflow(_opticalflow)
|
||||||
can_mgr(_can_mgr)
|
|
||||||
{
|
{
|
||||||
|
#if HAL_WITH_UAVCAN
|
||||||
|
if (_can_mgr == nullptr) {
|
||||||
|
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++)
|
||||||
|
can_mgr[i] = nullptr;
|
||||||
|
} else {
|
||||||
|
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++)
|
||||||
|
can_mgr[i] = _can_mgr[i];
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_HAL::init();
|
AP_HAL::init();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -93,5 +106,9 @@ public:
|
|||||||
AP_HAL::Scheduler* scheduler;
|
AP_HAL::Scheduler* scheduler;
|
||||||
AP_HAL::Util *util;
|
AP_HAL::Util *util;
|
||||||
AP_HAL::OpticalFlow *opticalflow;
|
AP_HAL::OpticalFlow *opticalflow;
|
||||||
AP_HAL::CANManager* can_mgr;
|
#if HAL_WITH_UAVCAN
|
||||||
|
AP_HAL::CANManager* can_mgr[MAX_NUMBER_OF_CAN_DRIVERS];
|
||||||
|
#else
|
||||||
|
AP_HAL::CANManager** can_mgr;
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user