mirror of https://github.com/ArduPilot/ardupilot
AP_AccelCal: added active() method
This commit is contained in:
parent
f53d80374b
commit
580cd143b8
|
@ -382,3 +382,9 @@ bool AP_AccelCal::gcs_vehicle_position(float position)
|
|||
|
||||
return false;
|
||||
}
|
||||
|
||||
// true if we are in a calibration process
|
||||
bool AP_AccelCal::active(void) const
|
||||
{
|
||||
return _status == ACCEL_CAL_WAITING_FOR_ORIENTATION || _status == ACCEL_CAL_COLLECTING_SAMPLE;
|
||||
}
|
||||
|
|
|
@ -36,6 +36,9 @@ public:
|
|||
|
||||
void handleMessage(const mavlink_message_t &msg);
|
||||
|
||||
// true if we are in a calibration process
|
||||
bool active(void) const;
|
||||
|
||||
private:
|
||||
GCS_MAVLINK *_gcs;
|
||||
bool _use_gcs_snoop;
|
||||
|
|
Loading…
Reference in New Issue