mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Replay: fixes for AP_Scheduler change
This commit is contained in:
parent
782ba00d4b
commit
26ced77ebc
@ -633,23 +633,7 @@ void Replay::setup()
|
||||
}
|
||||
|
||||
void Replay::set_ins_update_rate(uint16_t _update_rate) {
|
||||
switch (_update_rate) {
|
||||
case 50:
|
||||
_vehicle.ins.init(AP_InertialSensor::RATE_50HZ);
|
||||
break;
|
||||
case 100:
|
||||
_vehicle.ins.init(AP_InertialSensor::RATE_100HZ);
|
||||
break;
|
||||
case 200:
|
||||
_vehicle.ins.init(AP_InertialSensor::RATE_200HZ);
|
||||
break;
|
||||
case 400:
|
||||
_vehicle.ins.init(AP_InertialSensor::RATE_400HZ);
|
||||
break;
|
||||
default:
|
||||
printf("Invalid update rate (%d); use 50, 100, 200 or 400\n", _update_rate);
|
||||
exit(1);
|
||||
}
|
||||
_vehicle.ins.init(_update_rate);
|
||||
}
|
||||
|
||||
void Replay::inhibit_gyro_cal() {
|
||||
|
Loading…
Reference in New Issue
Block a user