From 26ced77ebceae710fedd4f408299a579008b7a00 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 26 Dec 2015 15:44:44 +1100 Subject: [PATCH] Replay: fixes for AP_Scheduler change --- Tools/Replay/Replay.cpp | 18 +----------------- 1 file changed, 1 insertion(+), 17 deletions(-) diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index 515f26c200..0a7a301986 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -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() {