ardupilot/ArduCopter/AP_State.pde

167 lines
3.3 KiB
Plaintext
Raw Normal View History

2012-11-10 01:43:43 -04:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void set_home_is_set(bool b)
{
// if no change, exit immediately
if( ap.home_is_set == b )
return;
2012-11-10 01:43:43 -04:00
ap.home_is_set = b;
if(b) {
Log_Write_Event(DATA_SET_HOME);
}
2012-11-10 01:43:43 -04:00
}
// ---------------------------------------------
void set_armed(bool b)
{
// if no change, exit immediately
if( ap.armed == b )
return;
2012-11-10 01:43:43 -04:00
ap.armed = b;
if(b){
Log_Write_Event(DATA_ARMED);
}else{
Log_Write_Event(DATA_DISARMED);
}
2012-11-10 01:43:43 -04:00
}
// ---------------------------------------------
void set_auto_armed(bool b)
{
// if no change, exit immediately
if( ap.auto_armed == b )
return;
ap.auto_armed = b;
if(b){
Log_Write_Event(DATA_AUTO_ARMED);
}
2012-11-10 01:43:43 -04:00
}
// ---------------------------------------------
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;
}
2012-11-10 01:43:43 -04:00
}
// ---------------------------------------------
static void set_failsafe_radio(bool mode)
2012-11-10 01:43:43 -04:00
{
// only act on changes
// -------------------
if(ap.failsafe_radio != mode) {
2012-11-10 01:43:43 -04:00
// store the value so we don't trip the gate twice
// -----------------------------------------------
ap.failsafe_radio = mode;
2012-11-10 01:43:43 -04:00
if (ap.failsafe_radio == false) {
2012-11-10 01:43:43 -04:00
// We've regained radio contact
// ----------------------------
failsafe_radio_off_event();
2012-11-10 01:43:43 -04:00
}else{
// We've lost radio contact
// ------------------------
failsafe_radio_on_event();
2012-11-10 01:43:43 -04:00
}
}
}
// ---------------------------------------------
void set_low_battery(bool b)
{
ap.low_battery = b;
2012-11-10 01:43:43 -04:00
}
// ---------------------------------------------
static void set_failsafe_gps(bool mode)
{
ap.failsafe_gps = mode;
}
2012-11-10 01:43:43 -04:00
// ---------------------------------------------
void set_takeoff_complete(bool b)
{
// if no change, exit immediately
if( ap.takeoff_complete == b )
return;
if(b){
Log_Write_Event(DATA_TAKEOFF);
}
ap.takeoff_complete = b;
2012-11-10 01:43:43 -04:00
}
// ---------------------------------------------
void set_land_complete(bool b)
{
// if no change, exit immediately
if( ap.land_complete == b )
return;
if(b){
Log_Write_Event(DATA_LAND_COMPLETE);
}
ap.land_complete = b;
2012-11-10 01:43:43 -04:00
}
// ---------------------------------------------
void set_alt_change(uint8_t flag){
// if no change, exit immediately
if( alt_change_flag == flag ) {
return;
}
// update flag
alt_change_flag = flag;
2012-11-10 01:43:43 -04:00
if(flag == REACHED_ALT){
Log_Write_Event(DATA_REACHED_ALT);
2012-11-10 01:43:43 -04:00
}else if(flag == ASCENDING){
Log_Write_Event(DATA_ASCENDING);
2012-11-10 01:43:43 -04:00
}else if(flag == DESCENDING){
Log_Write_Event(DATA_DESCENDING);
}
2012-11-10 01:43:43 -04:00
}
void set_compass_healthy(bool b)
{
if(ap.compass_status != b){
if(false == b){
Log_Write_Event(DATA_LOST_COMPASS);
}
}
ap.compass_status = b;
2012-11-10 01:43:43 -04:00
}
void set_gps_healthy(bool b)
{
if(ap.gps_status != b){
if(false == b){
Log_Write_Event(DATA_LOST_GPS);
}
}
ap.gps_status = b;
2012-11-10 01:43:43 -04:00
}
void dump_state()
{
cliSerial->printf("st: %u\n",ap.value);
2012-11-10 01:43:43 -04:00
}