Copter: ask for IMU samples at 100Hz

this produces the same result, but makes things simpler in the driver
This commit is contained in:
Andrew Tridgell 2013-08-02 18:48:03 +10:00
parent c083c15240
commit 2690edfc5f

View File

@ -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);