Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduCopter/AP_State.cpp
Views: 1798
#include "Copter.h"12// ---------------------------------------------3void Copter::set_auto_armed(bool b)4{5// if no change, exit immediately6if( ap.auto_armed == b )7return;89ap.auto_armed = b;10if(b){11LOGGER_WRITE_EVENT(LogEvent::AUTO_ARMED);12}13}1415// ---------------------------------------------16/**17* Set Simple mode18*19* @param [in] b 0:false or disabled, 1:true or SIMPLE, 2:SUPERSIMPLE20*/21void Copter::set_simple_mode(SimpleMode b)22{23if (simple_mode != b) {24switch (b) {25case SimpleMode::NONE:26LOGGER_WRITE_EVENT(LogEvent::SET_SIMPLE_OFF);27gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode off");28break;29case SimpleMode::SIMPLE:30LOGGER_WRITE_EVENT(LogEvent::SET_SIMPLE_ON);31gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode on");32break;33case SimpleMode::SUPERSIMPLE:34// initialise super simple heading35update_super_simple_bearing(true);36LOGGER_WRITE_EVENT(LogEvent::SET_SUPERSIMPLE_ON);37gcs().send_text(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on");38break;39}40simple_mode = b;41}42}4344// ---------------------------------------------45void Copter::set_failsafe_radio(bool b)46{47// only act on changes48// -------------------49if(failsafe.radio != b) {5051// store the value so we don't trip the gate twice52// -----------------------------------------------53failsafe.radio = b;5455if (failsafe.radio == false) {56// We've regained radio contact57// ----------------------------58failsafe_radio_off_event();59}else{60// We've lost radio contact61// ------------------------62failsafe_radio_on_event();63}6465// update AP_Notify66AP_Notify::flags.failsafe_radio = b;67}68}697071// ---------------------------------------------72void Copter::set_failsafe_gcs(bool b)73{74failsafe.gcs = b;7576// update AP_Notify77AP_Notify::flags.failsafe_gcs = b;78}7980// ---------------------------------------------8182void Copter::update_using_interlock()83{84#if FRAME_CONFIG == HELI_FRAME85// helicopters are always using motor interlock86ap.using_interlock = true;87#else88// check if we are using motor interlock control on an aux switch or are in throw mode89// which uses the interlock to stop motors while the copter is being thrown90ap.using_interlock = rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) != nullptr;91#endif92}939495