APM:Copter
mode_avoid_adsb.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  * control_avoid.cpp - init and run calls for AP_Avoidance's AVOID flight mode
5  *
6  * This re-uses GUIDED mode functions but does not interfere with the GCS or companion computer's
7  * use of guided mode because the velocity requests arrive from different sources (i.e MAVLink messages
8  * for GCS and Companion Computers vs the AP_Avoidance_Copter class for adsb avoidance) and inputs from
9  * each source are only accepted and processed in the appropriate flight mode.
10  */
11 
12 // initialise avoid_adsb controller
13 bool Copter::ModeAvoidADSB::init(const bool ignore_checks)
14 {
15  // re-use guided mode
16  return Copter::ModeGuided::init(ignore_checks);
17 }
18 
20 {
21  // check flight mode
22  if (copter.control_mode != AVOID_ADSB) {
23  return false;
24  }
25 
26  // re-use guided mode's velocity controller
28  return true;
29 }
30 
31 // runs the AVOID_ADSB controller
33 {
34  // re-use guided mode's velocity controller
35  // Note: this is safe from interference from GCSs and companion computer's whose guided mode
36  // position and velocity requests will be ignored while the vehicle is not in guided mode
38 }
bool set_velocity(const Vector3f &velocity_neu)
void run() override
void set_velocity(const Vector3f &velocity, bool use_yaw=false, float yaw_cd=0.0, bool use_yaw_rate=false, float yaw_rate_cds=0.0, bool yaw_relative=false, bool log_request=true)
bool init(bool ignore_checks) override
Definition: mode_guided.cpp:39
bool init(bool ignore_checks) override
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581