Browse Source

Rover: support raw IMU logging

master
Andrew Tridgell 10 years ago
parent
commit
fabee44583
  1. 2
      APMrover2/APMrover2.pde
  2. 1
      APMrover2/defines.h
  3. 3
      APMrover2/system.pde

2
APMrover2/APMrover2.pde

@ -737,6 +737,8 @@ static void one_second_loop(void) @@ -737,6 +737,8 @@ static void one_second_loop(void)
}
counter = 0;
}
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
}
static void update_GPS_50Hz(void)

1
APMrover2/defines.h

@ -89,6 +89,7 @@ enum mode { @@ -89,6 +89,7 @@ enum mode {
#define MASK_LOG_STEERING (1<<13)
#define MASK_LOG_RC (1<<14)
#define MASK_LOG_WHEN_DISARMED (1UL<<16)
#define MASK_LOG_IMU_RAW (1UL<<19)
// Waypoint Modes
// ----------------

3
APMrover2/system.pde

@ -248,6 +248,9 @@ static void startup_ground(void) @@ -248,6 +248,9 @@ static void startup_ground(void)
// so set serial ports non-blocking once we are ready to drive
serial_manager.set_blocking_writes_all(false);
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
ins.set_dataflash(&DataFlash);
gcs_send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to drive."));
}

Loading…
Cancel
Save