APM:Copter
mode_guided.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  * Init and run calls for guided flight mode
5  */
6 
7 #ifndef GUIDED_LOOK_AT_TARGET_MIN_DISTANCE_CM
8  # define GUIDED_LOOK_AT_TARGET_MIN_DISTANCE_CM 500 // point nose at target if it is more than 5m away
9 #endif
10 
11 #define GUIDED_POSVEL_TIMEOUT_MS 3000 // guided mode's position-velocity controller times out after 3seconds with no new updates
12 #define GUIDED_ATTITUDE_TIMEOUT_MS 1000 // guided mode's attitude controller times out after 1 second with no new updates
13 
14 static Vector3f guided_pos_target_cm; // position target (used by posvel controller only)
15 static Vector3f guided_vel_target_cms; // velocity target (used by velocity controller and posvel controller)
16 static uint32_t posvel_update_time_ms; // system time of last target update to posvel controller (i.e. position and velocity update)
17 static uint32_t vel_update_time_ms; // system time of last target update to velocity controller
18 
19 struct {
20  uint32_t update_time_ms;
21  float roll_cd;
22  float pitch_cd;
23  float yaw_cd;
24  float yaw_rate_cds;
27 } static guided_angle_state;
28 
29 struct Guided_Limit {
30  uint32_t timeout_ms; // timeout (in seconds) from the time that guided is invoked
31  float alt_min_cm; // lower altitude limit in cm above home (0 = no limit)
32  float alt_max_cm; // upper altitude limit in cm above home (0 = no limit)
33  float horiz_max_cm; // horizontal position limit in cm from where guided mode was initiated (0 = no limit)
34  uint32_t start_time;// system time in milliseconds that control was handed to the external computer
35  Vector3f start_pos; // start position as a distance from home in cm. used for checking horiz_max limit
36 } guided_limit;
37 
38 // guided_init - initialise guided controller
39 bool Copter::ModeGuided::init(bool ignore_checks)
40 {
41  if (copter.position_ok() || ignore_checks) {
42  // initialise yaw
43  auto_yaw.set_mode_to_default(false);
44  // start in position control mode
45  pos_control_start();
46  return true;
47  }else{
48  return false;
49  }
50 }
51 
52 
53 // guided_takeoff_start - initialises waypoint controller to implement take-off
54 bool Copter::ModeGuided::takeoff_start(float final_alt_above_home)
55 {
56  guided_mode = Guided_TakeOff;
57 
58  // initialise wpnav destination
59  Location_Class target_loc = copter.current_loc;
60  target_loc.set_alt_cm(final_alt_above_home, Location_Class::ALT_FRAME_ABOVE_HOME);
61 
62  if (!wp_nav->set_wp_destination(target_loc)) {
63  // failure to set destination can only be because of missing terrain data
65  // failure is propagated to GCS with NAK
66  return false;
67  }
68 
69  // initialise yaw
70  auto_yaw.set_mode(AUTO_YAW_HOLD);
71 
72  // clear i term when we're taking off
73  set_throttle_takeoff();
74 
75  // get initial alt for WP_NAVALT_MIN
76  copter.auto_takeoff_set_start_alt();
77 
78  return true;
79 }
80 
81 // initialise guided mode's position controller
83 {
84  // set to position control mode
85  guided_mode = Guided_WP;
86 
87  // initialise waypoint and spline controller
88  wp_nav->wp_and_spline_init();
89 
90  // initialise wpnav to stopping point
91  Vector3f stopping_point;
92  wp_nav->get_wp_stopping_point(stopping_point);
93 
94  // no need to check return status because terrain data is not used
95  wp_nav->set_wp_destination(stopping_point, false);
96 
97  // initialise yaw
98  auto_yaw.set_mode_to_default(false);
99 }
100 
101 // initialise guided mode's velocity controller
103 {
104  // set guided_mode to velocity controller
105  guided_mode = Guided_Velocity;
106 
107  // initialise horizontal speed, acceleration
108  pos_control->set_speed_xy(wp_nav->get_speed_xy());
109  pos_control->set_accel_xy(wp_nav->get_wp_acceleration());
110 
111  // initialize vertical speeds and acceleration
112  pos_control->set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
113  pos_control->set_accel_z(g.pilot_accel_z);
114 
115  // initialise velocity controller
116  pos_control->init_vel_controller_xyz();
117 }
118 
119 // initialise guided mode's posvel controller
121 {
122  // set guided_mode to velocity controller
123  guided_mode = Guided_PosVel;
124 
125  pos_control->init_xy_controller();
126 
127  // set speed and acceleration from wpnav's speed and acceleration
128  pos_control->set_speed_xy(wp_nav->get_speed_xy());
129  pos_control->set_accel_xy(wp_nav->get_wp_acceleration());
130 
131  const Vector3f& curr_pos = inertial_nav.get_position();
132  const Vector3f& curr_vel = inertial_nav.get_velocity();
133 
134  // set target position and velocity to current position and velocity
135  pos_control->set_xy_target(curr_pos.x, curr_pos.y);
136  pos_control->set_desired_velocity_xy(curr_vel.x, curr_vel.y);
137 
138  // set vertical speed and acceleration
139  pos_control->set_speed_z(wp_nav->get_speed_down(), wp_nav->get_speed_up());
140  pos_control->set_accel_z(wp_nav->get_accel_z());
141 
142  // pilot always controls yaw
143  auto_yaw.set_mode(AUTO_YAW_HOLD);
144 }
145 
146 // initialise guided mode's angle controller
148 {
149  // set guided_mode to velocity controller
150  guided_mode = Guided_Angle;
151 
152  // set vertical speed and acceleration
153  pos_control->set_speed_z(wp_nav->get_speed_down(), wp_nav->get_speed_up());
154  pos_control->set_accel_z(wp_nav->get_accel_z());
155 
156  // initialise position and desired velocity
157  if (!pos_control->is_active_z()) {
158  pos_control->set_alt_target_to_current_alt();
159  pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());
160  }
161 
162  // initialise targets
163  guided_angle_state.update_time_ms = millis();
167  guided_angle_state.climb_rate_cms = 0.0f;
168  guided_angle_state.yaw_rate_cds = 0.0f;
169  guided_angle_state.use_yaw_rate = false;
170 
171  // pilot always controls yaw
172  auto_yaw.set_mode(AUTO_YAW_HOLD);
173 }
174 
175 // guided_set_destination - sets guided mode's target destination
176 // Returns true if the fence is enabled and guided waypoint is within the fence
177 // else return false if the waypoint is outside the fence
178 bool Copter::ModeGuided::set_destination(const Vector3f& destination, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)
179 {
180  // ensure we are in position control mode
181  if (guided_mode != Guided_WP) {
182  pos_control_start();
183  }
184 
185 #if AC_FENCE == ENABLED
186  // reject destination if outside the fence
187  Location_Class dest_loc(destination);
188  if (!copter.fence.check_destination_within_fence(dest_loc)) {
190  // failure is propagated to GCS with NAK
191  return false;
192  }
193 #endif
194 
195  // set yaw state
196  set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
197 
198  // no need to check return status because terrain data is not used
199  wp_nav->set_wp_destination(destination, false);
200 
201  // log target
202  copter.Log_Write_GuidedTarget(guided_mode, destination, Vector3f());
203  return true;
204 }
205 
207 {
208  if (guided_mode != Guided_WP) {
209  return false;
210  }
211  return wp_nav->get_wp_destination(destination);
212 }
213 
214 // sets guided mode's target from a Location object
215 // returns false if destination could not be set (probably caused by missing terrain data)
216 // or if the fence is enabled and guided waypoint is outside the fence
217 bool Copter::ModeGuided::set_destination(const Location_Class& dest_loc, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)
218 {
219  // ensure we are in position control mode
220  if (guided_mode != Guided_WP) {
221  pos_control_start();
222  }
223 
224 #if AC_FENCE == ENABLED
225  // reject destination outside the fence.
226  // Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails
227  if (!copter.fence.check_destination_within_fence(dest_loc)) {
229  // failure is propagated to GCS with NAK
230  return false;
231  }
232 #endif
233 
234  if (!wp_nav->set_wp_destination(dest_loc)) {
235  // failure to set destination can only be because of missing terrain data
237  // failure is propagated to GCS with NAK
238  return false;
239  }
240 
241  // set yaw state
242  set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
243 
244  // log target
245  copter.Log_Write_GuidedTarget(guided_mode, Vector3f(dest_loc.lat, dest_loc.lng, dest_loc.alt),Vector3f());
246  return true;
247 }
248 
249 // guided_set_velocity - sets guided mode's target velocity
250 void Copter::ModeGuided::set_velocity(const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw, bool log_request)
251 {
252  // check we are in velocity control mode
253  if (guided_mode != Guided_Velocity) {
254  vel_control_start();
255  }
256 
257  // set yaw state
258  set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
259 
260  // record velocity target
261  guided_vel_target_cms = velocity;
263 
264  // log target
265  if (log_request) {
266  copter.Log_Write_GuidedTarget(guided_mode, Vector3f(), velocity);
267  }
268 }
269 
270 // set guided mode posvel target
271 bool Copter::ModeGuided::set_destination_posvel(const Vector3f& destination, const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)
272 {
273  // check we are in velocity control mode
274  if (guided_mode != Guided_PosVel) {
275  posvel_control_start();
276  }
277 
278 #if AC_FENCE == ENABLED
279  // reject destination if outside the fence
280  Location_Class dest_loc(destination);
281  if (!copter.fence.check_destination_within_fence(dest_loc)) {
283  // failure is propagated to GCS with NAK
284  return false;
285  }
286 #endif
287 
288  // set yaw state
289  set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
290 
292  guided_pos_target_cm = destination;
293  guided_vel_target_cms = velocity;
294 
295  copter.pos_control->set_pos_target(guided_pos_target_cm);
296 
297  // log target
298  copter.Log_Write_GuidedTarget(guided_mode, destination, velocity);
299  return true;
300 }
301 
302 // set guided mode angle target
303 void Copter::ModeGuided::set_angle(const Quaternion &q, float climb_rate_cms, bool use_yaw_rate, float yaw_rate_rads)
304 {
305  // check we are in velocity control mode
306  if (guided_mode != Guided_Angle) {
307  angle_control_start();
308  }
309 
310  // convert quaternion to euler angles
312  guided_angle_state.roll_cd = ToDeg(guided_angle_state.roll_cd) * 100.0f;
313  guided_angle_state.pitch_cd = ToDeg(guided_angle_state.pitch_cd) * 100.0f;
314  guided_angle_state.yaw_cd = wrap_180_cd(ToDeg(guided_angle_state.yaw_cd) * 100.0f);
315  guided_angle_state.yaw_rate_cds = ToDeg(yaw_rate_rads) * 100.0f;
316  guided_angle_state.use_yaw_rate = use_yaw_rate;
317 
318  guided_angle_state.climb_rate_cms = climb_rate_cms;
319  guided_angle_state.update_time_ms = millis();
320 
321  // interpret positive climb rate as triggering take-off
322  if (motors->armed() && !ap.auto_armed && (guided_angle_state.climb_rate_cms > 0.0f)) {
323  copter.set_auto_armed(true);
324  }
325 
326  // log target
327  copter.Log_Write_GuidedTarget(guided_mode,
329  Vector3f(0.0f, 0.0f, guided_angle_state.climb_rate_cms));
330 }
331 
332 // guided_run - runs the guided controller
333 // should be called at 100hz or more
335 {
336  // call the correct auto controller
337  switch (guided_mode) {
338 
339  case Guided_TakeOff:
340  // run takeoff controller
341  takeoff_run();
342  break;
343 
344  case Guided_WP:
345  // run position controller
346  pos_control_run();
347  break;
348 
349  case Guided_Velocity:
350  // run velocity controller
351  vel_control_run();
352  break;
353 
354  case Guided_PosVel:
355  // run position-velocity controller
356  posvel_control_run();
357  break;
358 
359  case Guided_Angle:
360  // run angle controller
361  angle_control_run();
362  break;
363  }
364  }
365 
366 // guided_takeoff_run - takeoff in guided mode
367 // called by guided_run at 100hz or more
369 {
370  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
371  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
372  // initialise wpnav targets
373  wp_nav->shift_wp_origin_to_current_pos();
374  zero_throttle_and_relax_ac();
375  // clear i term when we're taking off
376  set_throttle_takeoff();
377  return;
378  }
379 
380  // process pilot's yaw input
381  float target_yaw_rate = 0;
382  if (!copter.failsafe.radio) {
383  // get pilot's desired yaw rate
384  target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
385  }
386 
387 #if FRAME_CONFIG == HELI_FRAME
388  // helicopters stay in landed state until rotor speed runup has finished
389  if (motors->rotor_runup_complete()) {
390  set_land_complete(false);
391  } else {
392  // initialise wpnav targets
393  wp_nav->shift_wp_origin_to_current_pos();
394  }
395 #else
396  set_land_complete(false);
397 #endif
398 
399  // set motors to full range
401 
402  // run waypoint controller
403  copter.failsafe_terrain_set_status(wp_nav->update_wpnav());
404 
405  // call z-axis position controller (wpnav should have already updated it's alt target)
406  copter.pos_control->update_z_controller();
407 
408  // call attitude controller
409  copter.auto_takeoff_attitude_run(target_yaw_rate);
410 }
411 
412 // guided_pos_control_run - runs the guided position controller
413 // called from guided_run
415 {
416  // if not auto armed or motors not enabled set throttle to zero and exit immediately
417  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock() || ap.land_complete) {
418  zero_throttle_and_relax_ac();
419  return;
420  }
421 
422  // process pilot's yaw input
423  float target_yaw_rate = 0;
424  if (!copter.failsafe.radio) {
425  // get pilot's desired yaw rate
426  target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
427  if (!is_zero(target_yaw_rate)) {
428  auto_yaw.set_mode(AUTO_YAW_HOLD);
429  }
430  }
431 
432  // set motors to full range
434 
435  // run waypoint controller
436  copter.failsafe_terrain_set_status(wp_nav->update_wpnav());
437 
438  // call z-axis position controller (wpnav should have already updated it's alt target)
439  pos_control->update_z_controller();
440 
441  // call attitude controller
442  if (auto_yaw.mode() == AUTO_YAW_HOLD) {
443  // roll & pitch from waypoint controller, yaw rate from pilot
444  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate);
445  } else if (auto_yaw.mode() == AUTO_YAW_RATE) {
446  // roll & pitch from waypoint controller, yaw rate from mavlink command or mission item
447  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), auto_yaw.rate_cds());
448  } else {
449  // roll, pitch from waypoint controller, yaw heading from GCS or auto_heading()
450  attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), auto_yaw.yaw(), true);
451  }
452 }
453 
454 // guided_vel_control_run - runs the guided velocity controller
455 // called from guided_run
457 {
458  // if not auto armed or motors not enabled set throttle to zero and exit immediately
459  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock() || ap.land_complete) {
460  // initialise velocity controller
461  pos_control->init_vel_controller_xyz();
462  zero_throttle_and_relax_ac();
463  return;
464  }
465 
466  // process pilot's yaw input
467  float target_yaw_rate = 0;
468  if (!copter.failsafe.radio) {
469  // get pilot's desired yaw rate
470  target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
471  if (!is_zero(target_yaw_rate)) {
472  auto_yaw.set_mode(AUTO_YAW_HOLD);
473  }
474  }
475 
476  // set motors to full range
478 
479  // set velocity to zero and stop rotating if no updates received for 3 seconds
480  uint32_t tnow = millis();
482  if (!pos_control->get_desired_velocity().is_zero()) {
483  set_desired_velocity_with_accel_and_fence_limits(Vector3f(0.0f, 0.0f, 0.0f));
484  }
485  if (auto_yaw.mode() == AUTO_YAW_RATE) {
486  auto_yaw.set_rate(0.0f);
487  }
488  } else {
489  set_desired_velocity_with_accel_and_fence_limits(guided_vel_target_cms);
490  }
491 
492  // call velocity controller which includes z axis controller
493  pos_control->update_vel_controller_xyz(ekfNavVelGainScaler);
494 
495  // call attitude controller
496  if (auto_yaw.mode() == AUTO_YAW_HOLD) {
497  // roll & pitch from waypoint controller, yaw rate from pilot
498  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), target_yaw_rate);
499  } else if (auto_yaw.mode() == AUTO_YAW_RATE) {
500  // roll & pitch from velocity controller, yaw rate from mavlink command or mission item
501  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), auto_yaw.rate_cds());
502  } else {
503  // roll, pitch from waypoint controller, yaw heading from GCS or auto_heading()
504  attitude_control->input_euler_angle_roll_pitch_yaw(pos_control->get_roll(), pos_control->get_pitch(), auto_yaw.yaw(), true);
505  }
506 }
507 
508 // guided_posvel_control_run - runs the guided spline controller
509 // called from guided_run
511 {
512  // if not auto armed or motors not enabled set throttle to zero and exit immediately
513  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock() || ap.land_complete) {
514  // set target position and velocity to current position and velocity
515  pos_control->set_pos_target(inertial_nav.get_position());
516  pos_control->set_desired_velocity(Vector3f(0,0,0));
517  zero_throttle_and_relax_ac();
518  return;
519  }
520 
521  // process pilot's yaw input
522  float target_yaw_rate = 0;
523 
524  if (!copter.failsafe.radio) {
525  // get pilot's desired yaw rate
526  target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
527  if (!is_zero(target_yaw_rate)) {
528  auto_yaw.set_mode(AUTO_YAW_HOLD);
529  }
530  }
531 
532  // set motors to full range
534 
535  // set velocity to zero and stop rotating if no updates received for 3 seconds
536  uint32_t tnow = millis();
538  guided_vel_target_cms.zero();
539  if (auto_yaw.mode() == AUTO_YAW_RATE) {
540  auto_yaw.set_rate(0.0f);
541  }
542  }
543 
544  // calculate dt
545  float dt = pos_control->time_since_last_xy_update();
546 
547  // sanity check dt
548  if (dt >= 0.2f) {
549  dt = 0.0f;
550  }
551 
552  // advance position target using velocity target
553  guided_pos_target_cm += guided_vel_target_cms * dt;
554 
555  // send position and velocity targets to position controller
556  pos_control->set_pos_target(guided_pos_target_cm);
557  pos_control->set_desired_velocity_xy(guided_vel_target_cms.x, guided_vel_target_cms.y);
558 
559  // run position controllers
560  pos_control->update_xy_controller(ekfNavVelGainScaler);
561  pos_control->update_z_controller();
562 
563  // call attitude controller
564  if (auto_yaw.mode() == AUTO_YAW_HOLD) {
565  // roll & pitch from waypoint controller, yaw rate from pilot
566  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), target_yaw_rate);
567  } else if (auto_yaw.mode() == AUTO_YAW_RATE) {
568  // roll & pitch from position-velocity controller, yaw rate from mavlink command or mission item
569  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), auto_yaw.rate_cds());
570  } else {
571  // roll, pitch from waypoint controller, yaw heading from GCS or auto_heading()
572  attitude_control->input_euler_angle_roll_pitch_yaw(pos_control->get_roll(), pos_control->get_pitch(), auto_yaw.yaw(), true);
573  }
574 }
575 
576 // guided_angle_control_run - runs the guided angle controller
577 // called from guided_run
579 {
580  // if not auto armed or motors not enabled set throttle to zero and exit immediately
581  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock() || (ap.land_complete && guided_angle_state.climb_rate_cms <= 0.0f)) {
582 #if FRAME_CONFIG == HELI_FRAME
583  attitude_control->set_yaw_target_to_current_heading();
584 #endif
585  zero_throttle_and_relax_ac();
586  pos_control->relax_alt_hold_controllers(0.0f);
587  return;
588  }
589 
590  // constrain desired lean angles
591  float roll_in = guided_angle_state.roll_cd;
592  float pitch_in = guided_angle_state.pitch_cd;
593  float total_in = norm(roll_in, pitch_in);
594  float angle_max = MIN(attitude_control->get_althold_lean_angle_max(), copter.aparm.angle_max);
595  if (total_in > angle_max) {
596  float ratio = angle_max / total_in;
597  roll_in *= ratio;
598  pitch_in *= ratio;
599  }
600 
601  // wrap yaw request
602  float yaw_in = wrap_180_cd(guided_angle_state.yaw_cd);
603  float yaw_rate_in = wrap_180_cd(guided_angle_state.yaw_rate_cds);
604 
605  // constrain climb rate
606  float climb_rate_cms = constrain_float(guided_angle_state.climb_rate_cms, -fabsf(wp_nav->get_speed_down()), wp_nav->get_speed_up());
607 
608  // get avoidance adjusted climb rate
609  climb_rate_cms = get_avoidance_adjusted_climbrate(climb_rate_cms);
610 
611  // check for timeout - set lean angles and climb rate to zero if no updates received for 3 seconds
612  uint32_t tnow = millis();
613  if (tnow - guided_angle_state.update_time_ms > GUIDED_ATTITUDE_TIMEOUT_MS) {
614  roll_in = 0.0f;
615  pitch_in = 0.0f;
616  climb_rate_cms = 0.0f;
617  yaw_rate_in = 0.0f;
618  }
619 
620  // set motors to full range
622 
623  // call attitude controller
624  if (guided_angle_state.use_yaw_rate) {
625  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(roll_in, pitch_in, yaw_rate_in);
626  } else {
627  attitude_control->input_euler_angle_roll_pitch_yaw(roll_in, pitch_in, yaw_in, true);
628  }
629 
630  // call position controller
631  pos_control->set_alt_target_from_climb_rate_ff(climb_rate_cms, G_Dt, false);
632  pos_control->update_z_controller();
633 }
634 
635 // helper function to update position controller's desired velocity while respecting acceleration limits
637 {
638  // get current desired velocity
639  Vector3f curr_vel_des = pos_control->get_desired_velocity();
640 
641  // get change in desired velocity
642  Vector3f vel_delta = vel_des - curr_vel_des;
643 
644  // limit xy change
645  float vel_delta_xy = safe_sqrt(sq(vel_delta.x)+sq(vel_delta.y));
646  float vel_delta_xy_max = G_Dt * pos_control->get_accel_xy();
647  float ratio_xy = 1.0f;
648  if (!is_zero(vel_delta_xy) && (vel_delta_xy > vel_delta_xy_max)) {
649  ratio_xy = vel_delta_xy_max / vel_delta_xy;
650  }
651  curr_vel_des.x += (vel_delta.x * ratio_xy);
652  curr_vel_des.y += (vel_delta.y * ratio_xy);
653 
654  // limit z change
655  float vel_delta_z_max = G_Dt * pos_control->get_accel_z();
656  curr_vel_des.z += constrain_float(vel_delta.z, -vel_delta_z_max, vel_delta_z_max);
657 
658 #if AC_AVOID_ENABLED
659  // limit the velocity to prevent fence violations
660  copter.avoid.adjust_velocity(pos_control->get_pos_xy_p().kP(), pos_control->get_accel_xy(), curr_vel_des, G_Dt);
661  // get avoidance adjusted climb rate
662  curr_vel_des.z = get_avoidance_adjusted_climbrate(curr_vel_des.z);
663 #endif
664 
665  // update position controller with new target
666  pos_control->set_desired_velocity(curr_vel_des);
667 }
668 
669 // helper function to set yaw state and targets
670 void Copter::ModeGuided::set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle)
671 {
672  if (use_yaw) {
673  auto_yaw.set_fixed_yaw(yaw_cd / 100.0f, 0.0f, 0, relative_angle);
674  } else if (use_yaw_rate) {
675  auto_yaw.set_rate(yaw_rate_cds);
676  }
677 }
678 
679 // Guided Limit code
680 
681 // guided_limit_clear - clear/turn off guided limits
683 {
685  guided_limit.alt_min_cm = 0.0f;
686  guided_limit.alt_max_cm = 0.0f;
687  guided_limit.horiz_max_cm = 0.0f;
688 }
689 
690 // guided_limit_set - set guided timeout and movement limits
692 {
697 }
698 
699 // guided_limit_init_time_and_pos - initialise guided start time and position as reference for limit checking
700 // only called from AUTO mode's auto_nav_guided_start function
702 {
703  // initialise start time
705 
706  // initialise start position from current position
707  guided_limit.start_pos = inertial_nav.get_position();
708 }
709 
710 // guided_limit_check - returns true if guided mode has breached a limit
711 // used when guided is invoked from the NAV_GUIDED_ENABLE mission command
713 {
714  // check if we have passed the timeout
716  return true;
717  }
718 
719  // get current location
720  const Vector3f& curr_pos = inertial_nav.get_position();
721 
722  // check if we have gone below min alt
723  if (!is_zero(guided_limit.alt_min_cm) && (curr_pos.z < guided_limit.alt_min_cm)) {
724  return true;
725  }
726 
727  // check if we have gone above max alt
728  if (!is_zero(guided_limit.alt_max_cm) && (curr_pos.z > guided_limit.alt_max_cm)) {
729  return true;
730  }
731 
732  // check if we have gone beyond horizontal limit
733  if (guided_limit.horiz_max_cm > 0.0f) {
734  float horiz_move = get_horizontal_distance_cm(guided_limit.start_pos, curr_pos);
735  if (horiz_move > guided_limit.horiz_max_cm) {
736  return true;
737  }
738  }
739 
740  // if we got this far we must be within limits
741  return false;
742 }
743 
744 
746 {
747  switch(mode()) {
748  case Guided_WP:
749  return wp_nav->get_wp_distance_to_destination();
750  break;
751  case Guided_PosVel:
752  return pos_control->get_distance_to_target();
753  break;
754  default:
755  return 0;
756  }
757 }
758 
760 {
761  switch(mode()) {
762  case Guided_WP:
763  return wp_nav->get_wp_bearing_to_destination();
764  break;
765  case Guided_PosVel:
766  return pos_control->get_bearing_to_target();
767  break;
768  default:
769  return 0;
770  }
771 }
float norm(const T first, const U second, const Params... parameters)
void to_euler(float &roll, float &pitch, float &yaw) const
struct Guided_Limit guided_limit
bool set_destination_posvel(const Vector3f &destination, 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)
#define GUIDED_ATTITUDE_TIMEOUT_MS
Definition: mode_guided.cpp:12
float safe_sqrt(const T v)
float horiz_max_cm
Definition: mode_guided.cpp:33
AP_AHRS_NavEKF & ahrs
Vector3f start_pos
Definition: mode_guided.cpp:35
uint32_t start_time
Definition: mode_guided.cpp:34
float alt_min_cm
Definition: mode_guided.cpp:31
bool use_yaw_rate
Definition: mode_guided.cpp:26
void set_desired_velocity_with_accel_and_fence_limits(const Vector3f &vel_des)
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
#define ERROR_CODE_DEST_OUTSIDE_FENCE
Definition: defines.h:441
void set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle)
void run() override
float pitch_cd
Definition: mode_guided.cpp:22
static uint32_t vel_update_time_ms
Definition: mode_guided.cpp:17
int32_t lat
#define MIN(a, b)
int32_t roll_sensor
#define ToDeg(x)
AP_MotorsMatrix motors(400)
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 armed() const
static Vector3f guided_pos_target_cm
Definition: mode_guided.cpp:14
bool get_interlock() const
bool init(bool ignore_checks) override
Definition: mode_guided.cpp:39
bool get_wp(Location_Class &loc) override
#define ERROR_CODE_FAILED_TO_SET_DESTINATION
Definition: defines.h:438
float get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination)
int32_t alt
int32_t pitch_sensor
void limit_init_time_and_pos()
bool is_zero(const T fVal1)
#define f(i)
void set_angle(const Quaternion &q, float climb_rate_cms, bool use_yaw_rate, float yaw_rate_rads)
static Vector3f guided_vel_target_cms
Definition: mode_guided.cpp:15
uint32_t millis()
void limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm)
float alt_max_cm
Definition: mode_guided.cpp:32
struct @14 guided_angle_state
float roll_cd
Definition: mode_guided.cpp:21
DESIRED_THROTTLE_UNLIMITED
float constrain_float(const float amt, const float low, const float high)
float climb_rate_cms
Definition: mode_guided.cpp:25
void set_alt_cm(int32_t alt_cm, ALT_FRAME frame)
int32_t lng
bool set_destination(const Vector3f &destination, bool use_yaw=false, float yaw_cd=0.0, bool use_yaw_rate=false, float yaw_rate_cds=0.0, bool yaw_relative=false)
#define GUIDED_POSVEL_TIMEOUT_MS
Definition: mode_guided.cpp:11
uint32_t wp_distance() const override
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
bool takeoff_start(float final_alt_above_home)
Definition: mode_guided.cpp:54
int32_t wp_bearing() const override
virtual void set_desired_spool_state(enum spool_up_down_desired spool)
float sq(const T val)
float yaw_cd
Definition: mode_guided.cpp:23
uint32_t timeout_ms
Definition: mode_guided.cpp:30
int32_t yaw_sensor
static uint32_t posvel_update_time_ms
Definition: mode_guided.cpp:16
#define ERROR_SUBSYSTEM_NAVIGATION
Definition: defines.h:414
float yaw_rate_cds
Definition: mode_guided.cpp:24
uint32_t update_time_ms
Definition: mode_guided.cpp:20