ardupilot/ArduCopter/AP_State.cpp

129 lines
3.4 KiB
C++
Raw Normal View History

#include "Copter.h"
// set_home_state - update home state
void Copter::set_home_state(enum HomeState new_home_state)
2012-11-10 01:43:43 -04:00
{
// if no change, exit immediately
if (ap.home_state == new_home_state)
return;
2012-11-10 01:43:43 -04:00
// 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);
}
2012-11-10 01:43:43 -04:00
}
// home_is_set - returns true if home positions has been set (to GPS location, armed location or EKF origin)
bool Copter::home_is_set()
{
return (ap.home_state == HOME_SET_NOT_LOCKED || ap.home_state == HOME_SET_AND_LOCKED);
}
2012-11-10 01:43:43 -04:00
// ---------------------------------------------
void Copter::set_auto_armed(bool b)
2012-11-10 01:43:43 -04:00
{
// 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 Copter::set_simple_mode(uint8_t b)
2012-11-10 01:43:43 -04:00
{
if(ap.simple_mode != b){
switch (b) {
case 0:
Log_Write_Event(DATA_SET_SIMPLE_OFF);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SIMPLE mode off");
break;
case 1:
Log_Write_Event(DATA_SET_SIMPLE_ON);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SIMPLE mode on");
break;
default:
// initialise super simple heading
update_super_simple_bearing(true);
Log_Write_Event(DATA_SET_SUPERSIMPLE_ON);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on");
break;
}
ap.simple_mode = b;
}
2012-11-10 01:43:43 -04:00
}
// ---------------------------------------------
void Copter::set_failsafe_radio(bool b)
2012-11-10 01:43:43 -04:00
{
// only act on changes
// -------------------
if(failsafe.radio != b) {
2012-11-10 01:43:43 -04:00
// store the value so we don't trip the gate twice
// -----------------------------------------------
failsafe.radio = b;
2012-11-10 01:43:43 -04:00
if (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
}
// update AP_Notify
AP_Notify::flags.failsafe_radio = b;
2012-11-10 01:43:43 -04:00
}
}
// ---------------------------------------------
void Copter::set_failsafe_battery(bool b)
2012-11-10 01:43:43 -04:00
{
failsafe.battery = b;
AP_Notify::flags.failsafe_battery = b;
2012-11-10 01:43:43 -04:00
}
2013-04-29 09:30:22 -03:00
// ---------------------------------------------
void Copter::set_failsafe_gcs(bool b)
2013-04-29 09:30:22 -03:00
{
failsafe.gcs = b;
2013-04-29 09:30:22 -03:00
}
2012-11-10 01:43:43 -04:00
// ---------------------------------------------
void Copter::update_using_interlock()
{
#if FRAME_CONFIG == HELI_FRAME
// helicopters are always using motor interlock
ap.using_interlock = true;
#else
// check if we are using motor interlock control on an aux switch or are in throw mode
// which uses the interlock to stop motors while the copter is being thrown
ap.using_interlock = check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK);
#endif
}
void Copter::set_motor_emergency_stop(bool b)
2015-03-17 18:53:40 -03:00
{
if(ap.motor_emergency_stop != b) {
ap.motor_emergency_stop = b;
2015-03-17 18:53:40 -03:00
}
// Log new status
if (ap.motor_emergency_stop){
Log_Write_Event(DATA_MOTORS_EMERGENCY_STOPPED);
} else {
Log_Write_Event(DATA_MOTORS_EMERGENCY_STOP_CLEARED);
}
}