mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_HAL_ChibiOS: add missing override keywords
This was causing CubeOrange not to build
This commit is contained in:
parent
e05047bb0b
commit
35c2406b17
@ -176,15 +176,15 @@ class CanIface : public uavcan::ICanIface, uavcan::Noncopyable
|
||||
int computeTimings(uavcan::uint32_t target_bitrate, Timings& out_timings);
|
||||
|
||||
virtual uavcan::int16_t send(const uavcan::CanFrame& frame, uavcan::MonotonicTime tx_deadline,
|
||||
uavcan::CanIOFlags flags);
|
||||
uavcan::CanIOFlags flags) override;
|
||||
|
||||
virtual uavcan::int16_t receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic,
|
||||
uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags);
|
||||
uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags) override;
|
||||
|
||||
virtual uavcan::int16_t configureFilters(const uavcan::CanFilterConfig* filter_configs,
|
||||
uavcan::uint16_t num_configs);
|
||||
uavcan::uint16_t num_configs) override;
|
||||
|
||||
virtual uavcan::uint16_t getNumFilters() const;
|
||||
virtual uavcan::uint16_t getNumFilters() const override;
|
||||
|
||||
void setupMessageRam(void);
|
||||
|
||||
@ -240,7 +240,7 @@ public:
|
||||
* Total number of hardware failures and other kinds of errors (e.g. queue overruns).
|
||||
* May increase continuously if the interface is not connected to the bus.
|
||||
*/
|
||||
virtual uavcan::uint64_t getErrorCount() const;
|
||||
virtual uavcan::uint64_t getErrorCount() const override;
|
||||
|
||||
/**
|
||||
* Number of times the driver exercised library's requirement to abort transmission on first error.
|
||||
@ -303,7 +303,7 @@ class CanDriver : public uavcan::ICanDriver, uavcan::Noncopyable
|
||||
|
||||
virtual uavcan::int16_t select(uavcan::CanSelectMasks& inout_masks,
|
||||
const uavcan::CanFrame* (& pending_tx)[uavcan::MaxCanIfaces],
|
||||
uavcan::MonotonicTime blocking_deadline);
|
||||
uavcan::MonotonicTime blocking_deadline) override;
|
||||
|
||||
static void initOnce();
|
||||
static void initOnce(uavcan::uint8_t can_number, bool enable_irqs);
|
||||
@ -341,9 +341,9 @@ public:
|
||||
int init(const uavcan::uint32_t bitrate, const CanIface::OperatingMode mode);
|
||||
int init(const uavcan::uint32_t bitrate, const CanIface::OperatingMode mode, uavcan::uint8_t can_number);
|
||||
|
||||
virtual CanIface* getIface(uavcan::uint8_t iface_index);
|
||||
virtual CanIface* getIface(uavcan::uint8_t iface_index) override;
|
||||
|
||||
virtual uavcan::uint8_t getNumIfaces() const
|
||||
virtual uavcan::uint8_t getNumIfaces() const override
|
||||
{
|
||||
return num_ifaces_;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user