ardupilot/ArduCopter/AP_State.pde

152 lines
3.5 KiB
Plaintext

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// set_home_state - update home state
void set_home_state(enum HomeState new_home_state)
{
// if no change, exit immediately
if (ap.home_state == new_home_state)
return;
// update state
ap.home_state = new_home_state;
// log if home has been set
if (new_home_state == HOME_SET_NOT_LOCKED || new_home_state == HOME_SET_AND_LOCKED) {
Log_Write_Event(DATA_SET_HOME);
}
}
// home_is_set - returns true if home positions has been set (to GPS location, armed location or EKF origin)
bool home_is_set()
{
return (ap.home_state == HOME_SET_NOT_LOCKED || ap.home_state == HOME_SET_AND_LOCKED);
}
// ---------------------------------------------
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);
}
}
// ---------------------------------------------
void set_simple_mode(uint8_t b)
{
if(ap.simple_mode != b){
if(b == 0){
Log_Write_Event(DATA_SET_SIMPLE_OFF);
}else if(b == 1){
Log_Write_Event(DATA_SET_SIMPLE_ON);
}else{
// initialise super simple heading
update_super_simple_bearing(true);
Log_Write_Event(DATA_SET_SUPERSIMPLE_ON);
}
ap.simple_mode = b;
}
}
// ---------------------------------------------
static void set_failsafe_radio(bool b)
{
// only act on changes
// -------------------
if(failsafe.radio != b) {
// store the value so we don't trip the gate twice
// -----------------------------------------------
failsafe.radio = b;
if (failsafe.radio == false) {
// We've regained radio contact
// ----------------------------
failsafe_radio_off_event();
}else{
// We've lost radio contact
// ------------------------
failsafe_radio_on_event();
}
// update AP_Notify
AP_Notify::flags.failsafe_radio = b;
}
}
// ---------------------------------------------
void set_failsafe_battery(bool b)
{
failsafe.battery = b;
AP_Notify::flags.failsafe_battery = b;
}
// ---------------------------------------------
static void set_failsafe_gps(bool b)
{
failsafe.gps = b;
// update AP_Notify
AP_Notify::flags.failsafe_gps = b;
}
// ---------------------------------------------
static void set_failsafe_gcs(bool b)
{
failsafe.gcs = b;
}
// ---------------------------------------------
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);
}else{
Log_Write_Event(DATA_NOT_LANDED);
}
ap.land_complete = b;
}
// ---------------------------------------------
// set land complete maybe flag
void set_land_complete_maybe(bool b)
{
// if no change, exit immediately
if (ap.land_complete_maybe == b)
return;
if (b) {
Log_Write_Event(DATA_LAND_COMPLETE_MAYBE);
}
ap.land_complete_maybe = b;
}
// ---------------------------------------------
void set_pre_arm_check(bool b)
{
if(ap.pre_arm_check != b) {
ap.pre_arm_check = b;
AP_Notify::flags.pre_arm_check = b;
}
}
void set_pre_arm_rc_check(bool b)
{
if(ap.pre_arm_rc_check != b) {
ap.pre_arm_rc_check = b;
}
}