From 2690edfc5fdf47052941530819702f1f96c49bac Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 2 Aug 2013 18:48:03 +1000 Subject: [PATCH] Copter: ask for IMU samples at 100Hz this produces the same result, but makes things simpler in the driver --- ArduCopter/ArduCopter.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 447d610404..ec7cc7bd7d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -170,7 +170,7 @@ static DataFlash_Empty DataFlash; //////////////////////////////////////////////////////////////////////////////// // the rate we run the main loop at //////////////////////////////////////////////////////////////////////////////// -static const AP_InertialSensor::Sample_rate ins_sample_rate = AP_InertialSensor::RATE_200HZ; +static const AP_InertialSensor::Sample_rate ins_sample_rate = AP_InertialSensor::RATE_100HZ; //////////////////////////////////////////////////////////////////////////////// // Sensors @@ -937,7 +937,7 @@ void loop() // We want this to execute fast // ---------------------------- - if (ins.num_samples_available() >= 2) { + if (ins.num_samples_available() >= 1) { // check loop time perf_info_check_loop_time(timer - fast_loopTimer);