mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Compass: rename enum values to avoid header conflicts for 'ERROR'
This commit is contained in:
parent
963e5c5977
commit
be3d6c924e
@ -299,7 +299,7 @@ AP_Compass_AK8963::AP_Compass_AK8963(Compass &compass) :
|
||||
AP_Compass_Backend(compass),
|
||||
_backend(NULL),
|
||||
_initialised(false),
|
||||
_state(CONVERSION),
|
||||
_state(STATE_CONVERSION),
|
||||
_last_update_timestamp(0),
|
||||
_last_accum_time(0)
|
||||
{
|
||||
@ -458,15 +458,15 @@ void AP_Compass_AK8963::_update()
|
||||
|
||||
switch (_state)
|
||||
{
|
||||
case CONVERSION:
|
||||
case STATE_CONVERSION:
|
||||
_start_conversion();
|
||||
_state = SAMPLE;
|
||||
_state = STATE_SAMPLE;
|
||||
break;
|
||||
case SAMPLE:
|
||||
case STATE_SAMPLE:
|
||||
_collect_samples();
|
||||
_state = CONVERSION;
|
||||
_state = STATE_CONVERSION;
|
||||
break;
|
||||
case ERROR:
|
||||
case STATE_ERROR:
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
|
@ -54,9 +54,9 @@ protected:
|
||||
private:
|
||||
typedef enum
|
||||
{
|
||||
CONVERSION,
|
||||
SAMPLE,
|
||||
ERROR
|
||||
STATE_CONVERSION,
|
||||
STATE_SAMPLE,
|
||||
STATE_ERROR
|
||||
} state_t;
|
||||
|
||||
virtual bool _backend_init() = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user