mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
added more time to IMU startup. added more accessors and removed private flag.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1702 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
b28fb0a63a
commit
887a034fe9
@ -98,7 +98,7 @@ AP_IMU_Oilpan::_init_gyro()
|
||||
_sensor_cal[j] = adc_in;
|
||||
}
|
||||
|
||||
for(int i = 0; i < 50; i++){
|
||||
for(int i = 0; i < 100; i++){
|
||||
for (int j = 0; j < 3; j++){
|
||||
adc_in = _adc->Ch(_sensors[j]);
|
||||
// Subtract temp compensated typical gyro bias
|
||||
|
@ -27,7 +27,8 @@ public:
|
||||
///
|
||||
AP_IMU_Oilpan(AP_ADC *adc, AP_Var::Key key) :
|
||||
_adc(adc),
|
||||
_sensor_cal(key, PSTR("IMU_SENSOR_CAL"), AP_Var::k_flag_no_auto_load)
|
||||
_sensor_cal(key, PSTR("IMU_SENSOR_CAL"))
|
||||
// _sensor_cal(key, PSTR("IMU_SENSOR_CAL"), AP_Var::k_flag_no_auto_load)
|
||||
{}
|
||||
|
||||
/// Do warm or cold start.
|
||||
@ -48,13 +49,16 @@ public:
|
||||
virtual bool update(void);
|
||||
|
||||
// for jason
|
||||
int ax() { return _sensor_cal[3]; }
|
||||
int ay() { return _sensor_cal[4]; }
|
||||
int az() { return _sensor_cal[5]; }
|
||||
float gx() { return _sensor_cal[0]; }
|
||||
float gy() { return _sensor_cal[1]; }
|
||||
float gz() { return _sensor_cal[2]; }
|
||||
float ax() { return _sensor_cal[3]; }
|
||||
float ay() { return _sensor_cal[4]; }
|
||||
float az() { return _sensor_cal[5]; }
|
||||
|
||||
void ax(const int v) { _sensor_cal[3] = v; }
|
||||
void ay(const int v) { _sensor_cal[4] = v; }
|
||||
void az(const int v) { _sensor_cal[5] = v; }
|
||||
void ax(const float v) { _sensor_cal[3] = v; }
|
||||
void ay(const float v) { _sensor_cal[4] = v; }
|
||||
void az(const float v) { _sensor_cal[5] = v; }
|
||||
|
||||
|
||||
private:
|
||||
|
Loading…
Reference in New Issue
Block a user