mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: add allocare method for periph
This commit is contained in:
parent
cb6891821e
commit
58ac399aa9
|
@ -319,8 +319,15 @@ void AP_Airspeed::init()
|
|||
}
|
||||
#endif
|
||||
|
||||
if (enabled(0)) {
|
||||
allocate();
|
||||
}
|
||||
}
|
||||
|
||||
void AP_Airspeed::allocate()
|
||||
{
|
||||
if (sensor[0] != nullptr) {
|
||||
// already initialised
|
||||
// already initialised, periph may call allocate several times to allow CAN detection
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
|
@ -67,8 +67,9 @@ public:
|
|||
|
||||
void set_fixedwing_parameters(const class AP_FixedWing *_fixed_wing_parameters);
|
||||
|
||||
|
||||
void init(void);
|
||||
void allocate();
|
||||
|
||||
|
||||
// indicate which bit in LOG_BITMASK indicates we should log airspeed readings
|
||||
void set_log_bit(uint32_t log_bit) { _log_bit = log_bit; }
|
||||
|
|
Loading…
Reference in New Issue