mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
Copter: start dataflash logging when arming
Stop nearly empty logs from being produced. Removed redundant armed bit from ap state.
This commit is contained in:
parent
58d5fab412
commit
cca05ee8ae
@ -13,21 +13,6 @@ void set_home_is_set(bool b)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// ---------------------------------------------
|
|
||||||
void set_armed(bool b)
|
|
||||||
{
|
|
||||||
// if no change, exit immediately
|
|
||||||
if( ap.armed == b )
|
|
||||||
return;
|
|
||||||
|
|
||||||
ap.armed = b;
|
|
||||||
if(b){
|
|
||||||
Log_Write_Event(DATA_ARMED);
|
|
||||||
}else{
|
|
||||||
Log_Write_Event(DATA_DISARMED);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// ---------------------------------------------
|
// ---------------------------------------------
|
||||||
void set_auto_armed(bool b)
|
void set_auto_armed(bool b)
|
||||||
{
|
{
|
||||||
|
@ -366,7 +366,7 @@ static union {
|
|||||||
|
|
||||||
uint8_t low_battery : 1; // 4 // Used to track if the battery is low - LED output flashes when the batt is low
|
uint8_t low_battery : 1; // 4 // Used to track if the battery is low - LED output flashes when the batt is low
|
||||||
uint8_t pre_arm_check : 1; // 5 // true if the radio and accel calibration have been performed
|
uint8_t pre_arm_check : 1; // 5 // true if the radio and accel calibration have been performed
|
||||||
uint8_t armed : 1; // 6
|
uint8_t logging_started : 1; // 6 // true if dataflash logging has started
|
||||||
uint8_t auto_armed : 1; // 7 // stops auto missions from beginning until throttle is raised
|
uint8_t auto_armed : 1; // 7 // stops auto missions from beginning until throttle is raised
|
||||||
|
|
||||||
uint8_t failsafe_radio : 1; // 8 // A status flag for the radio failsafe
|
uint8_t failsafe_radio : 1; // 8 // A status flag for the radio failsafe
|
||||||
|
@ -850,7 +850,10 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
|
|||||||
// start a new log
|
// start a new log
|
||||||
static void start_logging()
|
static void start_logging()
|
||||||
{
|
{
|
||||||
DataFlash.StartNewLog(sizeof(log_structure)/sizeof(log_structure[0]), log_structure);
|
if (g.log_bitmask != 0 && !ap.logging_started) {
|
||||||
|
ap.logging_started = true;
|
||||||
|
DataFlash.StartNewLog(sizeof(log_structure)/sizeof(log_structure[0]), log_structure);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#else // LOGGING_ENABLED
|
#else // LOGGING_ENABLED
|
||||||
|
@ -87,10 +87,12 @@ static void init_arm_motors()
|
|||||||
// which calibrates the IMU
|
// which calibrates the IMU
|
||||||
static bool did_ground_start = false;
|
static bool did_ground_start = false;
|
||||||
|
|
||||||
// disable failsafe because initialising everything takes a while
|
// disable cpu failsafe because initialising everything takes a while
|
||||||
failsafe_disable();
|
failsafe_disable();
|
||||||
|
|
||||||
//cliSerial->printf("\nARM\n");
|
// start dataflash
|
||||||
|
start_logging();
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||||
gcs_send_text_P(SEVERITY_HIGH, PSTR("ARMING MOTORS"));
|
gcs_send_text_P(SEVERITY_HIGH, PSTR("ARMING MOTORS"));
|
||||||
#endif
|
#endif
|
||||||
@ -144,7 +146,6 @@ static void init_arm_motors()
|
|||||||
|
|
||||||
// finally actually arm the motors
|
// finally actually arm the motors
|
||||||
motors.armed(true);
|
motors.armed(true);
|
||||||
set_armed(true);
|
|
||||||
|
|
||||||
// reenable failsafe
|
// reenable failsafe
|
||||||
failsafe_enable();
|
failsafe_enable();
|
||||||
@ -191,7 +192,6 @@ static void init_disarm_motors()
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
motors.armed(false);
|
motors.armed(false);
|
||||||
set_armed(false);
|
|
||||||
|
|
||||||
compass.save_offsets();
|
compass.save_offsets();
|
||||||
|
|
||||||
|
@ -176,9 +176,6 @@ static void init_ardupilot()
|
|||||||
do_erase_logs();
|
do_erase_logs();
|
||||||
gcs0.reset_cli_timeout();
|
gcs0.reset_cli_timeout();
|
||||||
}
|
}
|
||||||
if (g.log_bitmask != 0) {
|
|
||||||
start_logging();
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
Loading…
Reference in New Issue
Block a user