APM:Libraries
AP_Landing_Deepstall.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * AP_Landing_Deepstall.cpp - Landing logic handler for ArduPlane for deepstall landings
18  */
19 
20 #include "AP_Landing.h"
21 #include <GCS_MAVLink/GCS.h>
22 #include <AP_HAL/AP_HAL.h>
24 
25 // table of user settable parameters for deepstall
27 
28  // @Param: V_FWD
29  // @DisplayName: Deepstall forward velocity
30  // @Description: The forward velocity of the aircraft while stalled
31  // @Range: 0 20
32  // @Units: m/s
33  // @User: Advanced
34  AP_GROUPINFO("V_FWD", 1, AP_Landing_Deepstall, forward_speed, 1),
35 
36  // @Param: SLOPE_A
37  // @DisplayName: Deepstall slope a
38  // @Description: The a component of distance = a*wind + b
39  // @User: Advanced
40  AP_GROUPINFO("SLOPE_A", 2, AP_Landing_Deepstall, slope_a, 1),
41 
42  // @Param: SLOPE_B
43  // @DisplayName: Deepstall slope b
44  // @Description: The a component of distance = a*wind + b
45  // @User: Advanced
46  AP_GROUPINFO("SLOPE_B", 3, AP_Landing_Deepstall, slope_b, 1),
47 
48  // @Param: APP_EXT
49  // @DisplayName: Deepstall approach extension
50  // @Description: The forward velocity of the aircraft while stalled
51  // @Range: 10 200
52  // @Units: m
53  // @User: Advanced
54  AP_GROUPINFO("APP_EXT", 4, AP_Landing_Deepstall, approach_extension, 50),
55 
56  // @Param: V_DWN
57  // @DisplayName: Deepstall veloicty down
58  // @Description: The downward velocity of the aircraft while stalled
59  // @Range: 0 20
60  // @Units: m/s
61  // @User: Advanced
62  AP_GROUPINFO("V_DWN", 5, AP_Landing_Deepstall, down_speed, 2),
63 
64  // @Param: SLEW_SPD
65  // @DisplayName: Deepstall slew speed
66  // @Description: The speed at which the elevator slews to deepstall
67  // @Range: 0 2
68  // @Units: s
69  // @User: Advanced
70  AP_GROUPINFO("SLEW_SPD", 6, AP_Landing_Deepstall, slew_speed, 0.5),
71 
72  // @Param: ELEV_PWM
73  // @DisplayName: Deepstall elevator PWM
74  // @Description: The PWM value in microseconds for the elevator at full deflection in deepstall
75  // @Range: 900 2100
76  // @Units: PWM
77  // @User: Advanced
78  AP_GROUPINFO("ELEV_PWM", 7, AP_Landing_Deepstall, elevator_pwm, 1500),
79 
80  // @Param: ARSP_MAX
81  // @DisplayName: Deepstall enabled airspeed
82  // @Description: The maximum aispeed where the deepstall steering controller is allowed to have control
83  // @Range: 5 20
84  // @Units: m/s
85  // @User: Advanced
86  AP_GROUPINFO("ARSP_MAX", 8, AP_Landing_Deepstall, handoff_airspeed, 15.0),
87 
88  // @Param: ARSP_MIN
89  // @DisplayName: Deepstall minimum derating airspeed
90  // @Description: Deepstall lowest airspeed where the deepstall controller isn't allowed full control
91  // @Range: 5 20
92  // @Units: m/s
93  // @User: Advanced
94  AP_GROUPINFO("ARSP_MIN", 9, AP_Landing_Deepstall, handoff_lower_limit_airspeed, 10.0),
95 
96  // @Param: L1
97  // @DisplayName: Deepstall L1 period
98  // @Description: Deepstall L1 navigational controller period
99  // @Range: 5 50
100  // @Units: m
101  // @User: Advanced
102  AP_GROUPINFO("L1", 10, AP_Landing_Deepstall, L1_period, 30.0),
103 
104  // @Param: L1_I
105  // @DisplayName: Deepstall L1 I gain
106  // @Description: Deepstall L1 integratior gain
107  // @Range: 0 1
108  // @User: Advanced
109  AP_GROUPINFO("L1_I", 11, AP_Landing_Deepstall, L1_i, 0),
110 
111  // @Param: YAW_LIM
112  // @DisplayName: Deepstall yaw rate limit
113  // @Description: The yaw rate limit while navigating in deepstall
114  // @Range: 0 90
115  // @Units degrees per second
116  // @User: Advanced
117  AP_GROUPINFO("YAW_LIM", 12, AP_Landing_Deepstall, yaw_rate_limit, 10),
118 
119  // @Param: L1_TCON
120  // @DisplayName: Deepstall L1 time constant
121  // @Description: Time constant for deepstall L1 control
122  // @Range: 0 1
123  // @Units seconds
124  // @User: Advanced
125  AP_GROUPINFO("L1_TCON", 13, AP_Landing_Deepstall, time_constant, 0.4),
126 
127  // @Group: DS_
128  // @Path: ../PID/PID.cpp
129  AP_SUBGROUPINFO(ds_PID, "", 14, AP_Landing_Deepstall, PID),
130 
131  // @Param: ABORTALT
132  // @DisplayName: Deepstall minimum abort altitude
133  // @Description: The minimum altitude which the aircraft must be above to abort a deepstall landing
134  // @Range: 0 50
135  // @Units meters
136  // @User: Advanced
137  AP_GROUPINFO("ABORTALT", 15, AP_Landing_Deepstall, min_abort_alt, 0.0f),
138 
139  // @Param: AIL_SCL
140  // @DisplayName: Aileron landing gain scalaing
141  // @Description: A scalar to reduce or increase the aileron control
142  // @Range: 0 2.0
143  // @User: Advanced
144  AP_GROUPINFO("AIL_SCL", 16, AP_Landing_Deepstall, aileron_scalar, 1.0f),
145 
147 };
148 
149 
150 // if DEBUG_PRINTS is defined statustexts will be sent to the GCS for debug purposes
151 // #define DEBUG_PRINTS
152 
153 void AP_Landing_Deepstall::do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude)
154 {
156  ds_PID.reset();
157  L1_xtrack_i = 0.0f;
158  hold_level = false; // come out of yaw lock
159 
160  // load the landing point in, the rest of path building is deferred for a better wind estimate
161  memcpy(&landing_point, &cmd.content.location, sizeof(Location));
162 
164  approach_alt_offset = cmd.p1;
166  } else {
167  approach_alt_offset = 0.0f;
168  }
169 }
170 
171 // currently identical to the slope aborts
172 void AP_Landing_Deepstall::verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed)
173 {
174  // when aborting a landing, mimic the verify_takeoff with steering hold. Once
175  // the altitude has been reached, restart the landing sequence
176  throttle_suppressed = false;
177  landing.nav_controller->update_heading_hold(get_bearing_cd(prev_WP_loc, next_WP_loc));
178 }
179 
180 
181 /*
182  update navigation for landing
183  */
184 bool AP_Landing_Deepstall::verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
185  const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms,
186  const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range)
187 {
188  switch (stage) {
190  if (get_distance(current_loc, landing_point) > fabsf(2 * landing.aparm.loiter_radius)) {
192  return false;
193  }
195  loiter_sum_cd = 0; // reset the loiter counter
196  FALLTHROUGH;
198  {
201  // wait until the altitude is correct before considering a breakout
202  return false;
203  }
204  // only count loiter progress when within the target altitude
205  int32_t target_bearing = landing.nav_controller->target_bearing_cd();
206  int32_t delta = wrap_180_cd(target_bearing - last_target_bearing);
207  delta *= (landing_point.flags.loiter_ccw ? -1 : 1);
208  if (delta > 0) { // only accumulate turns in the correct direction
209  loiter_sum_cd += delta;
210  }
211  last_target_bearing = target_bearing;
212  if (loiter_sum_cd < 36000) {
213  // wait until we've done at least one complete loiter at the correct altitude
214  return false;
215  }
217  loiter_sum_cd = 0; // reset the loiter counter
218  FALLTHROUGH;
219  }
221  // rebuild the approach path if we have done less then a full circle to allow it to be
222  // more into the wind as the estimator continues to refine itself, and allow better
223  // compensation on windy days. This is limited to a single full circle though, as on
224  // a no wind day you could be in this loop forever otherwise.
225  if (loiter_sum_cd < 36000) {
226  build_approach_path(false);
227  }
228  if (!verify_breakout(current_loc, arc_entry, height - approach_alt_offset)) {
229  int32_t target_bearing = landing.nav_controller->target_bearing_cd();
230  int32_t delta = wrap_180_cd(target_bearing - last_target_bearing);
231  if (delta > 0) { // only accumulate turns in the correct direction
232  loiter_sum_cd += delta;
233  }
234  last_target_bearing = target_bearing;
236  return false;
237  }
239  memcpy(&breakout_location, &current_loc, sizeof(Location));
240  FALLTHROUGH;
242  if (get_distance(current_loc, arc_entry) > 2 * landing.aparm.loiter_radius) {
244  return false;
245  }
247  FALLTHROUGH;
248  case DEEPSTALL_STAGE_ARC:
249  {
250  Vector2f groundspeed = landing.ahrs.groundspeed_vector();
253  degrees(atan2f(-groundspeed.y, -groundspeed.x) + M_PI))) >= 10.0f)) {
255  return false;
256  }
258  }
259  FALLTHROUGH;
261  {
262  Location entry_point;
264 
265  float height_above_target;
267  landing.ahrs.get_relative_position_D_home(height_above_target);
268  height_above_target = -height_above_target;
269  } else {
270  Location position;
271  if (landing.ahrs.get_position(position)) {
272  height_above_target = (position.alt - landing_point.alt + approach_alt_offset * 100) * 1e-2f;
273  } else {
274  height_above_target = approach_alt_offset;
275  }
276  }
277 
278  const float travel_distance = predict_travel_distance(landing.ahrs.wind_estimate(), height_above_target, false);
279 
280  memcpy(&entry_point, &landing_point, sizeof(Location));
281  location_update(entry_point, target_heading_deg + 180.0, travel_distance);
282 
283  if (!location_passed_point(current_loc, arc_exit, entry_point)) {
284  if (location_passed_point(current_loc, arc_exit, extended_approach)) {
285  // this should never happen, but prevent against an indefinite fly away
287  }
288  return false;
289  }
290  predict_travel_distance(landing.ahrs.wind_estimate(), height_above_target, true);
293 
295  if (elevator != nullptr) {
296  // take the last used elevator angle as the starting deflection
297  // don't worry about bailing here if the elevator channel can't be found
298  // that will be handled within override_servos
299  initial_elevator_pwm = elevator->get_output_pwm();
300  }
301  }
302  FALLTHROUGH;
304  // while in deepstall the only thing verify needs to keep the extended approach point sufficently far away
307  return false;
308  default:
309  return true;
310  }
311 }
312 
314 {
315  if (stage != DEEPSTALL_STAGE_LAND) {
316  return false;
317  }
318 
320 
321  if (elevator == nullptr) {
322  // deepstalls are impossible without these channels, abort the process
323  gcs().send_text(MAV_SEVERITY_CRITICAL, "Deepstall: Unable to find the elevator channels");
325  return false;
326  }
327 
328  // calculate the progress on slewing the elevator
329  float slew_progress = 1.0f;
330  if (slew_speed > 0) {
331  slew_progress = (AP_HAL::millis() - stall_entry_time) / (100.0f * slew_speed);
332  }
333 
334  // mix the elevator to the correct value
336  slew_progress, 0.0f, 1.0f));
337 
338  // use the current airspeed to dictate the travel limits
339  float airspeed;
340  landing.ahrs.airspeed_estimate(&airspeed);
341 
342  // only allow the deepstall steering controller to run below the handoff airspeed
343  if (slew_progress >= 1.0f || airspeed <= handoff_airspeed) {
344  // run the steering conntroller
345  float pid = update_steering();
346 
347 
348  float travel_limit = constrain_float((handoff_airspeed - airspeed) /
350  0.5f + 0.5f,
351  0.5f, 1.0f);
352 
353  float output = constrain_float(pid, -travel_limit, travel_limit);
356  SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0); // this will normally be managed as part of landing,
357  // but termination needs to set throttle control here
358  }
359 
360  // hand off rudder control to deepstall controlled
361  return true;
362 }
363 
365 {
366  float current_altitude_d;
367  landing.ahrs.get_relative_position_D_home(current_altitude_d);
368 
369  if (is_zero(min_abort_alt) || -current_altitude_d > min_abort_alt) {
371  return true;
372  } else {
373  return false;
374  }
375 }
376 
378 {
379  return stage == DEEPSTALL_STAGE_LAND;
380 }
381 
383 {
384  return stage != DEEPSTALL_STAGE_LAND;
385 }
386 
388 {
389  return stage == DEEPSTALL_STAGE_LAND;
390 }
391 
393 {
394  memcpy(&location, &landing_point, sizeof(Location));
395  return true;
396 }
397 
399 {
402  return landing.pre_flare_airspeed * 100;
403  } else {
405  }
406 }
407 
409 {
410  CHECK_PAYLOAD_SIZE2(DEEPSTALL);
411  mavlink_msg_deepstall_send(
412  chan,
419  landing_point.alt * 0.01,
422  stage);
423  return true;
424 }
425 
427 {
428  return ds_PID.get_pid_info();
429 }
430 
431 void AP_Landing_Deepstall::Log(void) const {
432  const DataFlash_Class::PID_Info& pid_info = ds_PID.get_pid_info();
433  struct log_DSTL pkt = {
436  stage : (uint8_t)stage,
442  constrain_float(crosstrack_error * 1e2f, (float)INT16_MIN, (float)INT16_MAX) : 0),
444  constrain_float(predicted_travel_distance * 1e2f, (float)INT16_MIN, (float)INT16_MAX) : 0),
447  desired : pid_info.desired,
448  P : pid_info.P,
449  I : pid_info.I,
450  D : pid_info.D,
451  };
452  DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt));
453 }
454 
455 // termination handling, expected to set the servo outputs
457  // if we were not in a deepstall, mark us as being in one
460  ds_PID.reset();
461  L1_xtrack_i = 0.0f;
462  landing.flags.in_progress = true;
464 
466  build_approach_path(true);
467  } else {
468  hold_level = true;
469  }
470  }
471 
472  // set the servo ouptuts, this can fail, so this is the important return value for the AFS
473  return override_servos();
474 }
475 
476 void AP_Landing_Deepstall::build_approach_path(bool use_current_heading)
477 {
479 
481  // TODO: Support a user defined approach heading
482  target_heading_deg = use_current_heading ? landing.ahrs.yaw_sensor * 1e-2 : (degrees(atan2f(-wind.y, -wind.x)));
483 
484  memcpy(&extended_approach, &landing_point, sizeof(Location));
485  memcpy(&arc_exit, &landing_point, sizeof(Location));
486 
487  //extend the approach point to 1km away so that there is always a navigational target
489 
490  float expected_travel_distance = predict_travel_distance(wind, is_zero(approach_alt_offset) ? landing_point.alt * 0.01f : approach_alt_offset,
491  false);
492  float approach_extension_m = expected_travel_distance + approach_extension;
493  float loiter_radius_m_abs = fabsf(loiter_radius);
494  // an approach extensions must be at least half the loiter radius, or the aircraft has a
495  // decent chance to be misaligned on final approach
496  approach_extension_m = MAX(approach_extension_m, loiter_radius_m_abs * 0.5f);
497 
498  location_update(arc_exit, target_heading_deg + 180, approach_extension_m);
499  memcpy(&arc, &arc_exit, sizeof(Location));
500  memcpy(&arc_entry, &arc_exit, sizeof(Location));
501 
502  float arc_heading_deg = target_heading_deg + (landing_point.flags.loiter_ccw ? -90.0f : 90.0f);
503  location_update(arc, arc_heading_deg, loiter_radius_m_abs);
504  location_update(arc_entry, arc_heading_deg, loiter_radius_m_abs * 2);
505 
506 #ifdef DEBUG_PRINTS
507  // TODO: Send this information via a MAVLink packet
508  gcs().send_text(MAV_SEVERITY_INFO, "Arc: %3.8f %3.8f",
509  (double)(arc.lat / 1e7),(double)( arc.lng / 1e7));
510  gcs().send_text(MAV_SEVERITY_INFO, "Loiter en: %3.8f %3.8f",
511  (double)(arc_entry.lat / 1e7), (double)(arc_entry.lng / 1e7));
512  gcs().send_text(MAV_SEVERITY_INFO, "Loiter ex: %3.8f %3.8f",
513  (double)(arc_exit.lat / 1e7), (double)(arc_exit.lng / 1e7));
514  gcs().send_text(MAV_SEVERITY_INFO, "Extended: %3.8f %3.8f",
515  (double)(extended_approach.lat / 1e7), (double)(extended_approach.lng / 1e7));
516  gcs().send_text(MAV_SEVERITY_INFO, "Extended by: %f (%f)", (double)approach_extension_m,
517  (double)expected_travel_distance);
518  gcs().send_text(MAV_SEVERITY_INFO, "Target Heading: %3.1f", (double)target_heading_deg);
519 #endif // DEBUG_PRINTS
520 
521 }
522 
523 float AP_Landing_Deepstall::predict_travel_distance(const Vector3f wind, const float height, const bool print)
524 {
525  bool reverse = false;
526 
527  float course = radians(target_heading_deg);
528 
529  // a forward speed of 0 will result in a divide by 0
530  float forward_speed_ms = MAX(forward_speed, 0.1f);
531 
532  Vector2f wind_vec(wind.x, wind.y); // work with the 2D component of wind
533  float wind_length = MAX(wind_vec.length(), 0.05f); // always assume a slight wind to avoid divide by 0
534  Vector2f course_vec(cosf(course), sinf(course));
535 
536  float offset = course - atan2f(-wind.y, -wind.x);
537 
538  // estimator for how far the aircraft will travel while entering the stall
539  float stall_distance = slope_a * wind_length * cosf(offset) + slope_b;
540 
541  float theta = acosf(constrain_float((wind_vec * course_vec) / wind_length, -1.0f, 1.0f));
542  if ((course_vec % wind_vec) > 0) {
543  reverse = true;
544  theta *= -1;
545  }
546 
547  float cross_component = sinf(theta) * wind_length;
548  float estimated_crab_angle = asinf(constrain_float(cross_component / forward_speed_ms, -1.0f, 1.0f));
549  if (reverse) {
550  estimated_crab_angle *= -1;
551  }
552 
553  float estimated_forward = cosf(estimated_crab_angle) * forward_speed_ms + cosf(theta) * wind_length;
554 
555  if (is_positive(down_speed)) {
556  predicted_travel_distance = (estimated_forward * height / down_speed) + stall_distance;
557  } else {
558  // if we don't have a sane downward speed in a deepstall (IE not zero, and not
559  // an ascent) then just provide the stall_distance as a reasonable approximation
560  predicted_travel_distance = stall_distance;
561  }
562 
563  if(print) {
564  // allow printing the travel distances on the final entry as its used for tuning
565  gcs().send_text(MAV_SEVERITY_INFO, "Deepstall: Entry: %0.1f (m) Travel: %0.1f (m)",
566  (double)stall_distance, (double)predicted_travel_distance);
567  }
568 
570 }
571 
572 bool AP_Landing_Deepstall::verify_breakout(const Location &current_loc, const Location &target_loc,
573  const float height_error) const
574 {
575  Vector2f location_delta = location_diff(current_loc, target_loc);
576  const float heading_error = degrees(landing.ahrs.groundspeed_vector().angle(location_delta));
577 
578  // Check to see if the the plane is heading toward the land waypoint. We use 20 degrees (+/-10 deg)
579  // of margin so that the altitude to be within 5 meters of desired
580 
581  if (heading_error <= 10.0 && fabsf(height_error) < DEEPSTALL_LOITER_ALT_TOLERANCE) {
582  // Want to head in a straight line from _here_ to the next waypoint instead of center of loiter wp
583  return true;
584  }
585  return false;
586 }
587 
589 {
590  Location current_loc;
591  if ((!landing.ahrs.get_position(current_loc) || !landing.ahrs.healthy()) && !hold_level) {
592  // panic if no position source is available
593  // continue the stall but target just holding the wings held level as deepstall should be a minimal
594  // energy configuration on the aircraft, and if a position isn't available aborting would be worse
595  gcs().send_text(MAV_SEVERITY_CRITICAL, "Deepstall: Invalid data from AHRS. Holding level");
596  hold_level = true;
597  }
598 
599  float desired_change = 0.0f;
600 
601  if (!hold_level) {
602  uint32_t time = AP_HAL::millis();
603  float dt = constrain_float(time - last_time, (uint32_t)10UL, (uint32_t)200UL) * 1e-3;
604  last_time = time;
605 
607  ab.normalize();
608  Vector2f a_air = location_diff(arc_exit, current_loc);
609 
610  crosstrack_error = a_air % ab;
611  float sine_nu1 = constrain_float(crosstrack_error / MAX(L1_period, 0.1f), -0.7071f, 0.7107f);
612  float nu1 = asinf(sine_nu1);
613 
614  if (L1_i > 0) {
615  L1_xtrack_i += nu1 * L1_i / dt;
617  nu1 += L1_xtrack_i;
618  }
619  desired_change = wrap_PI(radians(target_heading_deg) + nu1 - landing.ahrs.yaw) / time_constant;
620  }
621 
622  float yaw_rate = landing.ahrs.get_gyro().z;
623  float yaw_rate_limit_rps = radians(yaw_rate_limit);
624  float error = wrap_PI(constrain_float(desired_change, -yaw_rate_limit_rps, yaw_rate_limit_rps) - yaw_rate);
625 
626 #ifdef DEBUG_PRINTS
627  gcs().send_text(MAV_SEVERITY_INFO, "x: %f e: %f r: %f d: %f",
628  (double)crosstrack_error,
629  (double)error,
630  (double)degrees(yaw_rate),
631  (double)location_diff(current_loc, landing_point).length());
632 #endif // DEBUG_PRINTS
633 
634  return ds_PID.get_pid(error);
635 }
secondary rudder channel
Definition: SRV_Channel.h:65
#define DEEPSTALL_LOITER_ALT_TOLERANCE
static const struct AP_Param::GroupInfo var_info[]
int32_t get_target_airspeed_cm(void) const
AP_AHRS & ahrs
Definition: AP_Landing.h:125
void location_update(struct Location &loc, float bearing, float distance)
Definition: location.cpp:115
bool is_on_approach(void) const
AP_Int16 loiter_radius
Definition: AP_Vehicle.h:46
void verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed)
bool get_target_altitude_location(Location &location)
virtual int32_t target_bearing_cd(void) const =0
virtual const Vector3f & get_gyro(void) const =0
virtual bool reached_loiter_target(void)=0
#define FALLTHROUGH
Definition: AP_Common.h:50
AP_Float pre_flare_airspeed
Definition: AP_Landing.h:144
virtual bool get_position(struct Location &loc) const =0
Interface definition for the various Ground Control System.
virtual void update_waypoint(const struct Location &prev_WP, const struct Location &next_WP, float dist_min=0.0f)=0
virtual Vector3f wind_estimate(void) const =0
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float get_distance(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:36
float desired
static SRV_Channel * get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1)
void WriteBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:481
virtual bool airspeed_estimate(float *airspeed_ret) const
Definition: AP_AHRS.cpp:170
GCS & gcs()
float yaw
Definition: AP_AHRS.h:226
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
Definition: AP_Math.cpp:111
void build_approach_path(bool use_current_heading)
void do_land(const AP_Mission::Mission_Command &cmd, const float relative_altitude)
virtual Vector2f groundspeed_vector(void)
Definition: AP_AHRS.cpp:235
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
float target_heading
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:56
virtual void update_loiter(const struct Location &center_WP, float radius, int8_t loiter_direction)=0
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
static int8_t delta
Definition: RCOutput.cpp:21
const DataFlash_Class::PID_Info & get_pid_info(void) const
Definition: PID.h:101
float angle(const Vector2< T > &v2) const
Definition: vector2.cpp:127
float predict_travel_distance(const Vector3f wind, const float height, const bool print)
T y
Definition: vector2.h:37
AP_Navigation * nav_controller
Definition: AP_Landing.h:127
float linear_interpolate(float low_output, float high_output, float var_value, float var_low, float var_high)
Definition: AP_Math.cpp:81
uint64_t time_us
float wrap_180(const T angle, float unit_mod)
Definition: AP_Math.cpp:96
virtual float loiter_radius(const float radius) const =0
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
int16_t travel_distance
#define CHECK_PAYLOAD_SIZE2(id)
Definition: GCS.h:30
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
Object managing one PID control.
Definition: PID.h:13
T y
Definition: vector3.h:67
Class managing Plane Deepstall landing methods.
uint32_t millis()
Definition: system.cpp:157
bool send_deepstall_message(mavlink_channel_t chan) const
void reset()
Reset the whole PID state.
Definition: PID.cpp:122
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
uint64_t micros64()
Definition: system.cpp:162
struct AP_Landing::@124 flags
bool verify_breakout(const Location &current_loc, const Location &target_loc, const float height_error) const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
int32_t target_alt
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
bool commanded_go_around
Definition: AP_Landing.h:112
bool is_throttle_suppressed(void) const
float length(void) const
Definition: vector2.cpp:24
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
Vector2f location
Definition: location.cpp:16
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
int32_t target_lat
uint16_t get_output_pwm(void) const
Definition: SRV_Channel.h:139
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void normalize()
Definition: vector2.h:140
float get_pid(float error, float scaler=1.0)
Definition: PID.cpp:37
virtual bool healthy(void) const =0
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
bool in_progress
Definition: AP_Landing.h:115
#define error(fmt, args ...)
AP_Vehicle::FixedWing & aparm
Definition: AP_Landing.h:129
int32_t target_lng
bool verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc, const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms, const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range)
#define degrees(x)
Definition: moduletest.c:23
#define M_PI
Definition: definitions.h:10
bool is_flying_forward(void) const
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
virtual void update_heading_hold(int32_t navigation_heading_cd)=0
bool location_passed_point(const struct Location &location, const struct Location &point1, const struct Location &point2)
Definition: location.cpp:80
int32_t yaw_sensor
Definition: AP_AHRS.h:231
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
void set_output_pwm(uint16_t pwm)
virtual void get_relative_position_D_home(float &posD) const =0
float l1_i
#define AP_GROUPEND
Definition: AP_Param.h:121
disarm_if_autoland_complete_fn_t disarm_if_autoland_complete_fn
Definition: AP_Landing.h:135
T x
Definition: vector3.h:67
AP_Int32 airspeed_cruise_cm
Definition: AP_Vehicle.h:38
const DataFlash_Class::PID_Info & get_pid_info(void) const