Rover: update for new ins interface

This commit is contained in:
Andrew Tridgell 2012-11-29 22:57:10 +11:00
parent 45e62add9f
commit 94f73b83c3
4 changed files with 16 additions and 4 deletions

View File

@ -167,6 +167,10 @@ DataFlash_APM2 DataFlash(&spi3_semaphore);
DataFlash_APM1 DataFlash;
#endif
////////////////////////////////////////////////////////////////////////////////
// the rate we run the main loop at
////////////////////////////////////////////////////////////////////////////////
static const AP_InertialSensor::Sample_rate ins_sample_rate = AP_InertialSensor::RATE_50HZ;
////////////////////////////////////////////////////////////////////////////////
// Parameters

View File

@ -319,7 +319,9 @@ static int8_t
setup_accel_scale(uint8_t argc, const Menu::arg *argv)
{
cliSerial->println_P(PSTR("Initialising gyros"));
ins.init(AP_InertialSensor::COLD_START, delay, flash_leds, &timer_scheduler);
ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate,
delay, flash_leds, &timer_scheduler);
if (ins.calibrate_accel(delay, flash_leds, setup_printf_P, setup_wait_key)) {
if (g.manual_level == 0) {
cliSerial->println_P(PSTR("Setting MANUAL_LEVEL to 1"));

View File

@ -447,7 +447,9 @@ static void startup_INS_ground(bool force_accel_level)
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Beginning INS calibration; do not move plane"));
mavlink_delay(1000);
ins.init(AP_InertialSensor::COLD_START, mavlink_delay, flash_leds, &timer_scheduler);
ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate,
mavlink_delay, flash_leds, &timer_scheduler);
if (force_accel_level || g.manual_level == 0) {
// when MANUAL_LEVEL is set to 1 we don't do accelerometer
// levelling on each boot, and instead rely on the user to do

View File

@ -465,7 +465,9 @@ static int8_t
test_ins(uint8_t argc, const Menu::arg *argv)
{
//cliSerial->printf_P(PSTR("Calibrating."));
ins.init(AP_InertialSensor::COLD_START, delay, flash_leds, &timer_scheduler);
ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate,
delay, flash_leds, &timer_scheduler);
ahrs.reset();
print_hit_enter();
@ -526,7 +528,9 @@ test_mag(uint8_t argc, const Menu::arg *argv)
report_compass();
// we need the AHRS initialised for this test
ins.init(AP_InertialSensor::COLD_START, delay, flash_leds, &timer_scheduler);
ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate,
delay, flash_leds, &timer_scheduler);
ahrs.reset();
int counter = 0;