mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: add missing uavcan-related override keywords
This commit is contained in:
parent
be173a9514
commit
54b200a777
|
@ -139,17 +139,17 @@ void setUtcSyncParams(const UtcSyncParams& params);
|
|||
class SystemClock : public uavcan::ISystemClock, uavcan::Noncopyable {
|
||||
SystemClock() { }
|
||||
|
||||
virtual void adjustUtc(uavcan::UtcDuration adjustment)
|
||||
virtual void adjustUtc(uavcan::UtcDuration adjustment) override
|
||||
{
|
||||
clock::adjustUtc(adjustment);
|
||||
}
|
||||
|
||||
public:
|
||||
virtual uavcan::MonotonicTime getMonotonic() const
|
||||
virtual uavcan::MonotonicTime getMonotonic() const override
|
||||
{
|
||||
return clock::getMonotonic();
|
||||
}
|
||||
virtual uavcan::UtcTime getUtc() const
|
||||
virtual uavcan::UtcTime getUtc() const override
|
||||
{
|
||||
return clock::getUtc();
|
||||
}
|
||||
|
|
|
@ -174,15 +174,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
|
||||
{
|
||||
return NumFilters;
|
||||
}
|
||||
|
@ -252,7 +252,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.
|
||||
|
@ -307,7 +307,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);
|
||||
|
@ -345,9 +345,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_;
|
||||
}
|
||||
|
|
|
@ -36,8 +36,8 @@ public:
|
|||
|
||||
#ifdef ENABLE_HEAP
|
||||
// heap functions, note that a heap once alloc'd cannot be dealloc'd
|
||||
virtual void *allocate_heap_memory(size_t size);
|
||||
virtual void *heap_realloc(void *heap, void *ptr, size_t new_size);
|
||||
virtual void *allocate_heap_memory(size_t size) override;
|
||||
virtual void *heap_realloc(void *heap, void *ptr, size_t new_size) override;
|
||||
#endif // ENABLE_HEAP
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue