mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_HAL: move to having ICanDriver as member instead of inheriting it
this is to support having drivers using libuavcan supplied helper objects, a method which can lead to much less duplication of code
This commit is contained in:
parent
f0f4239d4a
commit
d539a157b7
@ -92,8 +92,10 @@ public:
|
|||||||
/**
|
/**
|
||||||
* Generic CAN driver.
|
* Generic CAN driver.
|
||||||
*/
|
*/
|
||||||
class AP_HAL::CANManager: public uavcan::ICanDriver {
|
class AP_HAL::CANManager {
|
||||||
public:
|
public:
|
||||||
|
CANManager(uavcan::ICanDriver* driver) : _driver(driver) {}
|
||||||
|
|
||||||
/* CAN port open method
|
/* CAN port open method
|
||||||
Opens port with specified bit rate
|
Opens port with specified bit rate
|
||||||
bitrate - selects the speed that the port will be configured to. If zero, the port speed is left
|
bitrate - selects the speed that the port will be configured to. If zero, the port speed is left
|
||||||
@ -115,6 +117,9 @@ public:
|
|||||||
|
|
||||||
virtual AP_UAVCAN *get_UAVCAN(void) = 0;
|
virtual AP_UAVCAN *get_UAVCAN(void) = 0;
|
||||||
virtual void set_UAVCAN(AP_UAVCAN *uavcan) = 0;
|
virtual void set_UAVCAN(AP_UAVCAN *uavcan) = 0;
|
||||||
|
uavcan::ICanDriver* get_driver() { return _driver; }
|
||||||
|
private:
|
||||||
|
uavcan::ICanDriver* _driver;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user