mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: reduce redundant event logging
We now only write state changes to the dataflash log when they have changed. Also replaced <tab> with <space> in AP_State.pde
This commit is contained in:
parent
af478d52bc
commit
b4bbae56c6
|
@ -3,43 +3,55 @@
|
|||
|
||||
void set_home_is_set(bool b)
|
||||
{
|
||||
ap.home_is_set = b;
|
||||
// if no change, exit immediately
|
||||
if( ap.home_is_set == b )
|
||||
return;
|
||||
|
||||
if(b) Log_Write_Event(DATA_SET_HOME);
|
||||
ap.home_is_set = b;
|
||||
if(b) {
|
||||
Log_Write_Event(DATA_SET_HOME);
|
||||
}
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
void set_armed(bool b)
|
||||
{
|
||||
ap.armed = b;
|
||||
if(b){
|
||||
Log_Write_Event(DATA_ARMED);
|
||||
// if no change, exit immediately
|
||||
if( ap.armed == b )
|
||||
return;
|
||||
|
||||
}else{
|
||||
Log_Write_Event(DATA_DISARMED);
|
||||
}
|
||||
ap.armed = b;
|
||||
if(b){
|
||||
Log_Write_Event(DATA_ARMED);
|
||||
}else{
|
||||
Log_Write_Event(DATA_DISARMED);
|
||||
}
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
void set_auto_armed(bool b)
|
||||
{
|
||||
ap.auto_armed = b;
|
||||
if(b){
|
||||
Log_Write_Event(DATA_AUTO_ARMED);
|
||||
}
|
||||
// if no change, exit immediately
|
||||
if( ap.auto_armed == b )
|
||||
return;
|
||||
|
||||
ap.auto_armed = b;
|
||||
if(b){
|
||||
Log_Write_Event(DATA_AUTO_ARMED);
|
||||
}
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
void set_simple_mode(bool b)
|
||||
{
|
||||
if(ap.simple_mode != b){
|
||||
if(b){
|
||||
Log_Write_Event(DATA_SET_SIMPLE_ON);
|
||||
}else{
|
||||
Log_Write_Event(DATA_SET_SIMPLE_OFF);
|
||||
}
|
||||
}
|
||||
ap.simple_mode = b;
|
||||
if(ap.simple_mode != b){
|
||||
if(b){
|
||||
Log_Write_Event(DATA_SET_SIMPLE_ON);
|
||||
}else{
|
||||
Log_Write_Event(DATA_SET_SIMPLE_OFF);
|
||||
}
|
||||
ap.simple_mode = b;
|
||||
}
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
|
@ -69,25 +81,33 @@ static void set_failsafe(bool mode)
|
|||
// ---------------------------------------------
|
||||
void set_low_battery(bool b)
|
||||
{
|
||||
ap.low_battery = b;
|
||||
ap.low_battery = b;
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
void set_takeoff_complete(bool b)
|
||||
{
|
||||
if(b){
|
||||
Log_Write_Event(DATA_TAKEOFF);
|
||||
}
|
||||
ap.takeoff_complete = b;
|
||||
// if no change, exit immediately
|
||||
if( ap.takeoff_complete == b )
|
||||
return;
|
||||
|
||||
if(b){
|
||||
Log_Write_Event(DATA_TAKEOFF);
|
||||
}
|
||||
ap.takeoff_complete = b;
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
void set_land_complete(bool b)
|
||||
{
|
||||
if(b){
|
||||
Log_Write_Event(DATA_LAND_COMPLETE);
|
||||
}
|
||||
ap.land_complete = b;
|
||||
// if no change, exit immediately
|
||||
if( ap.land_complete == b )
|
||||
return;
|
||||
|
||||
if(b){
|
||||
Log_Write_Event(DATA_LAND_COMPLETE);
|
||||
}
|
||||
ap.land_complete = b;
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
|
@ -100,41 +120,40 @@ void set_alt_change(uint8_t flag){
|
|||
}
|
||||
|
||||
// update flag
|
||||
alt_change_flag = flag;
|
||||
alt_change_flag = flag;
|
||||
|
||||
if(flag == REACHED_ALT){
|
||||
Log_Write_Event(DATA_REACHED_ALT);
|
||||
if(flag == REACHED_ALT){
|
||||
Log_Write_Event(DATA_REACHED_ALT);
|
||||
|
||||
}else if(flag == ASCENDING){
|
||||
Log_Write_Event(DATA_ASCENDING);
|
||||
}else if(flag == ASCENDING){
|
||||
Log_Write_Event(DATA_ASCENDING);
|
||||
|
||||
}else if(flag == DESCENDING){
|
||||
Log_Write_Event(DATA_DESCENDING);
|
||||
}
|
||||
}else if(flag == DESCENDING){
|
||||
Log_Write_Event(DATA_DESCENDING);
|
||||
}
|
||||
}
|
||||
|
||||
void set_compass_healthy(bool b)
|
||||
{
|
||||
if(ap.compass_status != b){
|
||||
if(false == b){
|
||||
Log_Write_Event(DATA_LOST_COMPASS);
|
||||
}
|
||||
}
|
||||
ap.compass_status = b;
|
||||
if(ap.compass_status != b){
|
||||
if(false == b){
|
||||
Log_Write_Event(DATA_LOST_COMPASS);
|
||||
}
|
||||
}
|
||||
ap.compass_status = b;
|
||||
}
|
||||
|
||||
void set_gps_healthy(bool b)
|
||||
{
|
||||
if(ap.gps_status != b){
|
||||
if(false == b){
|
||||
Log_Write_Event(DATA_LOST_GPS);
|
||||
}
|
||||
}
|
||||
ap.gps_status = b;
|
||||
if(ap.gps_status != b){
|
||||
if(false == b){
|
||||
Log_Write_Event(DATA_LOST_GPS);
|
||||
}
|
||||
}
|
||||
ap.gps_status = b;
|
||||
}
|
||||
|
||||
void dump_state()
|
||||
{
|
||||
cliSerial->printf("st: %u\n",ap.value);
|
||||
//cliSerial->printf("%u\n", *(uint16_t*)&ap);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue