mirror of https://github.com/ArduPilot/ardupilot
Replay: set INS_GYRO_CAL to never to avoid losing samples
This commit is contained in:
parent
79dee5aaa9
commit
5da7d6eac2
|
@ -280,6 +280,7 @@ private:
|
||||||
} user_parameters[100];
|
} user_parameters[100];
|
||||||
|
|
||||||
void set_ins_update_rate(uint16_t update_rate);
|
void set_ins_update_rate(uint16_t update_rate);
|
||||||
|
void inhibit_gyro_cal();
|
||||||
|
|
||||||
void usage(void);
|
void usage(void);
|
||||||
void set_user_parameters(void);
|
void set_user_parameters(void);
|
||||||
|
@ -608,6 +609,7 @@ void Replay::setup()
|
||||||
|
|
||||||
_vehicle.setup();
|
_vehicle.setup();
|
||||||
|
|
||||||
|
inhibit_gyro_cal();
|
||||||
set_ins_update_rate(log_info.update_rate);
|
set_ins_update_rate(log_info.update_rate);
|
||||||
|
|
||||||
feenableexcept(FE_INVALID | FE_OVERFLOW);
|
feenableexcept(FE_INVALID | FE_OVERFLOW);
|
||||||
|
@ -648,6 +650,19 @@ void Replay::set_ins_update_rate(uint16_t _update_rate) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void Replay::inhibit_gyro_cal() {
|
||||||
|
// swiped from LR_MsgHandler.cpp; until we see PARM messages, we
|
||||||
|
// don't have a PARM handler available to set parameters.
|
||||||
|
enum ap_var_type var_type;
|
||||||
|
AP_Param *vp = AP_Param::find("INS_GYR_CAL", &var_type);
|
||||||
|
if (vp == NULL) {
|
||||||
|
::fprintf(stderr, "No GYR_CAL parameter found\n");
|
||||||
|
abort();
|
||||||
|
}
|
||||||
|
((AP_Float *)vp)->set(AP_InertialSensor::GYRO_CAL_NEVER);
|
||||||
|
|
||||||
|
// logreader.set_parameter("GYR_CAL", AP_InertialSensor::GYRO_CAL_NEVER);
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
setup user -p parameters
|
setup user -p parameters
|
||||||
|
|
Loading…
Reference in New Issue