APM:Copter
avoidance_adsb.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 #include <AP_Notify/AP_Notify.h>
3 
4 #if ADSB_ENABLED == ENABLED
6 {
7  adsb.update();
9 }
10 
11 #include <stdio.h>
12 
13 MAV_COLLISION_ACTION AP_Avoidance_Copter::handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action)
14 {
15  MAV_COLLISION_ACTION actual_action = requested_action;
16  bool failsafe_state_change = false;
17 
18  // check for changes in failsafe
19  if (!copter.failsafe.adsb) {
20  copter.failsafe.adsb = true;
21  failsafe_state_change = true;
22  // record flight mode in case it's required for the recovery
23  prev_control_mode = copter.control_mode;
24  }
25 
26  // take no action in some flight modes
27  if (copter.control_mode == LAND ||
29  copter.control_mode == THROW ||
30 #endif
31  copter.control_mode == FLIP) {
32  actual_action = MAV_COLLISION_ACTION_NONE;
33  }
34 
35  // if landed and we will take some kind of action, just disarm
36  if ((actual_action > MAV_COLLISION_ACTION_REPORT) && copter.should_disarm_on_failsafe()) {
37  copter.init_disarm_motors();
38  actual_action = MAV_COLLISION_ACTION_NONE;
39  } else {
40 
41  // take action based on requested action
42  switch (actual_action) {
43 
44  case MAV_COLLISION_ACTION_RTL:
45  // attempt to switch to RTL, if this fails (i.e. flying in manual mode with bad position) do nothing
46  if (failsafe_state_change) {
47  if (!copter.set_mode(RTL, MODE_REASON_AVOIDANCE)) {
48  actual_action = MAV_COLLISION_ACTION_NONE;
49  }
50  }
51  break;
52 
53  case MAV_COLLISION_ACTION_HOVER:
54  // attempt to switch to Loiter, if this fails (i.e. flying in manual mode with bad position) do nothing
55  if (failsafe_state_change) {
56  if (!copter.set_mode(LOITER, MODE_REASON_AVOIDANCE)) {
57  actual_action = MAV_COLLISION_ACTION_NONE;
58  }
59  }
60  break;
61 
62  case MAV_COLLISION_ACTION_ASCEND_OR_DESCEND:
63  // climb or descend to avoid obstacle
64  if (!handle_avoidance_vertical(obstacle, failsafe_state_change)) {
65  actual_action = MAV_COLLISION_ACTION_NONE;
66  }
67  break;
68 
69  case MAV_COLLISION_ACTION_MOVE_HORIZONTALLY:
70  // move horizontally to avoid obstacle
71  if (!handle_avoidance_horizontal(obstacle, failsafe_state_change)) {
72  actual_action = MAV_COLLISION_ACTION_NONE;
73  }
74  break;
75 
76  case MAV_COLLISION_ACTION_MOVE_PERPENDICULAR:
77  if (!handle_avoidance_perpendicular(obstacle, failsafe_state_change)) {
78  actual_action = MAV_COLLISION_ACTION_NONE;
79  }
80  break;
81 
82  // unsupported actions and those that require no response
83  case MAV_COLLISION_ACTION_NONE:
84  return actual_action;
85  case MAV_COLLISION_ACTION_REPORT:
86  default:
87  break;
88  }
89  }
90 
91  // log to dataflash
92  if (failsafe_state_change) {
93  copter.Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_ADSB, actual_action);
94  }
95 
96  // return with action taken
97  return actual_action;
98 }
99 
100 void AP_Avoidance_Copter::handle_recovery(uint8_t recovery_action)
101 {
102  // check we are coming out of failsafe
103  if (copter.failsafe.adsb) {
104  copter.failsafe.adsb = false;
106 
107  // restore flight mode if requested and user has not changed mode since
108  if (copter.control_mode_reason == MODE_REASON_AVOIDANCE) {
109  switch (recovery_action) {
110 
112  // do nothing, we'll stay in the AVOID_ADSB mode which is guided which will loiter forever
113  break;
114 
116  set_mode_else_try_RTL_else_LAND(prev_control_mode);
117  break;
118 
120  set_mode_else_try_RTL_else_LAND(RTL);
121  break;
122 
124  if (prev_control_mode == AUTO) {
125  set_mode_else_try_RTL_else_LAND(AUTO);
126  }
127  break;
128 
129  default:
130  break;
131  } // switch
132  }
133  }
134 }
135 
137 {
138  if (!copter.set_mode(mode, MODE_REASON_AVOIDANCE_RECOVERY)) {
139  // on failure RTL or LAND
140  if (!copter.set_mode(RTL, MODE_REASON_AVOIDANCE_RECOVERY)) {
142  }
143  }
144 }
145 
146 // check flight mode is avoid_adsb
147 bool AP_Avoidance_Copter::check_flightmode(bool allow_mode_change)
148 {
149  // ensure copter is in avoid_adsb mode
150  if (allow_mode_change && copter.control_mode != AVOID_ADSB) {
151  if (!copter.set_mode(AVOID_ADSB, MODE_REASON_AVOIDANCE)) {
152  // failed to set mode so exit immediately
153  return false;
154  }
155  }
156 
157  // check flight mode
158  return (copter.control_mode == AVOID_ADSB);
159 }
160 
161 bool AP_Avoidance_Copter::handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change)
162 {
163  // ensure copter is in avoid_adsb mode
164  if (!check_flightmode(allow_mode_change)) {
165  return false;
166  }
167 
168  // decide on whether we should climb or descend
169  bool should_climb = false;
170  Location my_loc;
171  if (_ahrs.get_position(my_loc)) {
172  should_climb = my_loc.alt > obstacle->_location.alt;
173  }
174 
175  // get best vector away from obstacle
176  Vector3f velocity_neu;
177  if (should_climb) {
178  velocity_neu.z = copter.wp_nav->get_speed_up();
179  } else {
180  velocity_neu.z = -copter.wp_nav->get_speed_down();
181  // do not descend if below RTL alt
182  if (copter.current_loc.alt < copter.g.rtl_altitude) {
183  velocity_neu.z = 0.0f;
184  }
185  }
186 
187  // send target velocity
188  copter.mode_avoid_adsb.set_velocity(velocity_neu);
189  return true;
190 }
191 
193 {
194  // ensure copter is in avoid_adsb mode
195  if (!check_flightmode(allow_mode_change)) {
196  return false;
197  }
198 
199  // get best vector away from obstacle
200  Vector3f velocity_neu;
201  if (get_vector_perpendicular(obstacle, velocity_neu)) {
202  // remove vertical component
203  velocity_neu.z = 0.0f;
204  // check for divide by zero
205  if (is_zero(velocity_neu.x) && is_zero(velocity_neu.y)) {
206  return false;
207  }
208  // re-normalise
209  velocity_neu.normalize();
210  // convert horizontal components to velocities
211  velocity_neu.x *= copter.wp_nav->get_speed_xy();
212  velocity_neu.y *= copter.wp_nav->get_speed_xy();
213  // send target velocity
214  copter.mode_avoid_adsb.set_velocity(velocity_neu);
215  return true;
216  }
217 
218  // if we got this far we failed to set the new target
219  return false;
220 }
221 
223 {
224  // ensure copter is in avoid_adsb mode
225  if (!check_flightmode(allow_mode_change)) {
226  return false;
227  }
228 
229  // get best vector away from obstacle
230  Vector3f velocity_neu;
231  if (get_vector_perpendicular(obstacle, velocity_neu)) {
232  // convert horizontal components to velocities
233  velocity_neu.x *= copter.wp_nav->get_speed_xy();
234  velocity_neu.y *= copter.wp_nav->get_speed_xy();
235  // use up and down waypoint speeds
236  if (velocity_neu.z > 0.0f) {
237  velocity_neu.z *= copter.wp_nav->get_speed_up();
238  } else {
239  velocity_neu.z *= copter.wp_nav->get_speed_down();
240  // do not descend if below RTL alt
241  if (copter.current_loc.alt < copter.g.rtl_altitude) {
242  velocity_neu.z = 0.0f;
243  }
244  }
245  // send target velocity
246  copter.mode_avoid_adsb.set_velocity(velocity_neu);
247  return true;
248  }
249 
250  // if we got this far we failed to set the new target
251  return false;
252 }
253 #endif
void avoidance_adsb_update(void)
control_mode_t
Definition: defines.h:91
AP_Avoidance_Copter avoidance_adsb
Definition: Copter.h:579
void set_mode_else_try_RTL_else_LAND(control_mode_t mode)
Definition: defines.h:95
uint8_t adsb
Definition: Copter.h:401
bool check_flightmode(bool allow_mode_change)
control_mode_t prev_control_mode
Definition: Copter.h:348
Definition: defines.h:100
bool handle_avoidance_perpendicular(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change)
#define AP_AVOIDANCE_RECOVERY_REMAIN_IN_AVOID_ADSB
#define MODE_THROW_ENABLED
Definition: config.h:349
int32_t alt
bool is_zero(const T fVal1)
#define AP_AVOIDANCE_RECOVERY_RTL
bool handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change)
Definition: defines.h:103
Definition: defines.h:97
Definition: defines.h:107
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
#define ERROR_SUBSYSTEM_FAILSAFE_ADSB
Definition: defines.h:412
#define AP_AVOIDANCE_RECOVERY_RESUME_PREVIOUS_FLIGHTMODE
bool handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change)
#define ERROR_CODE_ERROR_RESOLVED
Definition: defines.h:418
void handle_recovery(uint8_t recovery_action) override
#define ENABLED
Definition: defines.h:6
MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) override
#define AP_AVOIDANCE_RECOVERY_RESUME_IF_AUTO_ELSE_LOITER
Definition: defines.h:98