mirror of https://github.com/ArduPilot/ardupilot
Replay: remove INS start style
This commit is contained in:
parent
b6229288a1
commit
803ca92f73
|
@ -604,16 +604,16 @@ void Replay::setup()
|
||||||
void Replay::set_ins_update_rate(uint16_t _update_rate) {
|
void Replay::set_ins_update_rate(uint16_t _update_rate) {
|
||||||
switch (_update_rate) {
|
switch (_update_rate) {
|
||||||
case 50:
|
case 50:
|
||||||
_vehicle.ins.init(AP_InertialSensor::WARM_START, AP_InertialSensor::RATE_50HZ);
|
_vehicle.ins.init(AP_InertialSensor::RATE_50HZ);
|
||||||
break;
|
break;
|
||||||
case 100:
|
case 100:
|
||||||
_vehicle.ins.init(AP_InertialSensor::WARM_START, AP_InertialSensor::RATE_100HZ);
|
_vehicle.ins.init(AP_InertialSensor::RATE_100HZ);
|
||||||
break;
|
break;
|
||||||
case 200:
|
case 200:
|
||||||
_vehicle.ins.init(AP_InertialSensor::WARM_START, AP_InertialSensor::RATE_200HZ);
|
_vehicle.ins.init(AP_InertialSensor::RATE_200HZ);
|
||||||
break;
|
break;
|
||||||
case 400:
|
case 400:
|
||||||
_vehicle.ins.init(AP_InertialSensor::WARM_START, AP_InertialSensor::RATE_400HZ);
|
_vehicle.ins.init(AP_InertialSensor::RATE_400HZ);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
printf("Invalid update rate (%d); use 50, 100, 200 or 400\n", _update_rate);
|
printf("Invalid update rate (%d); use 50, 100, 200 or 400\n", _update_rate);
|
||||||
|
|
Loading…
Reference in New Issue