mirror of https://github.com/ArduPilot/ardupilot
Mount: Alexmos save 4 bytes of RAM
This commit is contained in:
parent
7a8fe5f4d4
commit
66d2328163
|
@ -294,20 +294,20 @@ private:
|
|||
} _buffer,_current_parameters;
|
||||
|
||||
AP_HAL::UARTDriver *_port;
|
||||
bool _initialised;
|
||||
bool _initialised : 1;
|
||||
|
||||
// result of the get_boardinfo
|
||||
uint8_t _board_version;
|
||||
float _current_firmware_version;
|
||||
uint8_t _firmware_beta_version;
|
||||
bool _gimbal_3axis;
|
||||
bool _gimbal_bat_monitoring;
|
||||
bool _gimbal_3axis : 1;
|
||||
bool _gimbal_bat_monitoring : 1;
|
||||
|
||||
// keep the last _current_angle values
|
||||
Vector3f _current_angle;
|
||||
|
||||
// CMD_READ_PARAMS has been called once
|
||||
bool _param_read_once;
|
||||
bool _param_read_once : 1;
|
||||
|
||||
// Serial Protocol Variables
|
||||
uint8_t _checksum;
|
||||
|
@ -317,7 +317,7 @@ private:
|
|||
uint8_t _payload_counter;
|
||||
|
||||
// confirmed that last command was ok
|
||||
bool _last_command_confirmed;
|
||||
bool _last_command_confirmed : 1;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue