added ability to zero out the accels
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1115 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
ddd2b585f8
commit
e3e8dbb0b3
@ -171,6 +171,14 @@ AP_IMU::init_accel(void) // 3, 4, 5
|
||||
save_accel_eeprom();
|
||||
}
|
||||
|
||||
void
|
||||
AP_IMU::zero_accel(void) // 3, 4, 5
|
||||
{
|
||||
_adc_offset[3] = 0;
|
||||
_adc_offset[4] = 0;
|
||||
_adc_offset[5] = 0;
|
||||
save_accel_eeprom();
|
||||
}
|
||||
/**************************************************/
|
||||
// Returns the temperature compensated raw gyro value
|
||||
//---------------------------------------------------
|
||||
|
@ -23,6 +23,7 @@ public:
|
||||
void init(void); // inits both
|
||||
void init_accel(void); // just Accels
|
||||
void init_gyro(void); // just gyros
|
||||
void zero_accel(void);
|
||||
|
||||
void load_gyro_eeprom(void);
|
||||
void save_gyro_eeprom(void);
|
||||
|
Loading…
Reference in New Issue
Block a user