Browse Source

Copter: suspend logging while disarmed

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
84881470b1
  1. 28
      ArduCopter/Log.pde
  2. 3
      ArduCopter/motors.pde

28
ArduCopter/Log.pde

@ -799,19 +799,23 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page) @@ -799,19 +799,23 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
// start a new log
static void start_logging()
{
if (g.log_bitmask != 0 && !ap.logging_started) {
ap.logging_started = true;
DataFlash.StartNewLog();
DataFlash.Log_Write_Message_P(PSTR(FIRMWARE_STRING));
// write system identifier as well if available
char sysid[40];
if (hal.util->get_system_id(sysid)) {
DataFlash.Log_Write_Message(sysid);
if (g.log_bitmask != 0) {
if (!ap.logging_started) {
ap.logging_started = true;
DataFlash.StartNewLog();
DataFlash.Log_Write_Message_P(PSTR(FIRMWARE_STRING));
// write system identifier as well if available
char sysid[40];
if (hal.util->get_system_id(sysid)) {
DataFlash.Log_Write_Message(sysid);
}
// log the flight mode
Log_Write_Mode(control_mode);
}
// log the flight mode
Log_Write_Mode(control_mode);
// enable writes
DataFlash.EnableWrites(true);
}
}

3
ArduCopter/motors.pde

@ -503,6 +503,9 @@ static void init_disarm_motors() @@ -503,6 +503,9 @@ static void init_disarm_motors()
// log disarm to the dataflash
Log_Write_Event(DATA_DISARMED);
// suspend logging
DataFlash.EnableWrites(false);
// disable gps velocity based centrefugal force compensation
ahrs.set_correct_centrifugal(false);
}

Loading…
Cancel
Save