APM:Libraries
AC_WPNav.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include "AC_WPNav.h"
3 
4 extern const AP_HAL::HAL& hal;
5 
7  // index 0 was used for the old orientation matrix
8 
9  // @Param: SPEED
10  // @DisplayName: Waypoint Horizontal Speed Target
11  // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally during a WP mission
12  // @Units: cm/s
13  // @Range: 20 2000
14  // @Increment: 50
15  // @User: Standard
16  AP_GROUPINFO("SPEED", 0, AC_WPNav, _wp_speed_cms, WPNAV_WP_SPEED),
17 
18  // @Param: RADIUS
19  // @DisplayName: Waypoint Radius
20  // @Description: Defines the distance from a waypoint, that when crossed indicates the wp has been hit.
21  // @Units: cm
22  // @Range: 10 1000
23  // @Increment: 1
24  // @User: Standard
25  AP_GROUPINFO("RADIUS", 1, AC_WPNav, _wp_radius_cm, WPNAV_WP_RADIUS),
26 
27  // @Param: SPEED_UP
28  // @DisplayName: Waypoint Climb Speed Target
29  // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while climbing during a WP mission
30  // @Units: cm/s
31  // @Range: 10 1000
32  // @Increment: 50
33  // @User: Standard
34  AP_GROUPINFO("SPEED_UP", 2, AC_WPNav, _wp_speed_up_cms, WPNAV_WP_SPEED_UP),
35 
36  // @Param: SPEED_DN
37  // @DisplayName: Waypoint Descent Speed Target
38  // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while descending during a WP mission
39  // @Units: cm/s
40  // @Range: 10 500
41  // @Increment: 10
42  // @User: Standard
43  AP_GROUPINFO("SPEED_DN", 3, AC_WPNav, _wp_speed_down_cms, WPNAV_WP_SPEED_DOWN),
44 
45  // @Param: ACCEL
46  // @DisplayName: Waypoint Acceleration
47  // @Description: Defines the horizontal acceleration in cm/s/s used during missions
48  // @Units: cm/s/s
49  // @Range: 50 500
50  // @Increment: 10
51  // @User: Standard
52  AP_GROUPINFO("ACCEL", 5, AC_WPNav, _wp_accel_cmss, WPNAV_ACCELERATION),
53 
54  // @Param: ACCEL_Z
55  // @DisplayName: Waypoint Vertical Acceleration
56  // @Description: Defines the vertical acceleration in cm/s/s used during missions
57  // @Units: cm/s/s
58  // @Range: 50 500
59  // @Increment: 10
60  // @User: Standard
61  AP_GROUPINFO("ACCEL_Z", 6, AC_WPNav, _wp_accel_z_cmss, WPNAV_WP_ACCEL_Z_DEFAULT),
62 
63  // @Param: RFND_USE
64  // @DisplayName: Waypoint missions use rangefinder for terrain following
65  // @Description: This controls if waypoint missions use rangefinder for terrain following
66  // @Values: 0:Disable,1:Enable
67  // @User: Advanced
68  AP_GROUPINFO("RFND_USE", 10, AC_WPNav, _rangefinder_use, 1),
69 
71 };
72 
73 // Default constructor.
74 // Note that the Vector/Matrix constructors already implicitly zero
75 // their values.
76 //
77 AC_WPNav::AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control) :
78  _inav(inav),
79  _ahrs(ahrs),
80  _pos_control(pos_control),
81  _attitude_control(attitude_control),
82  _wp_last_update(0),
83  _wp_step(0),
84  _track_length(0.0f),
85  _track_length_xy(0.0f),
86  _track_desired(0.0f),
87  _limited_speed_xy_cms(0.0f),
88  _track_accel(0.0f),
89  _track_speed(0.0f),
90  _track_leash_length(0.0f),
91  _slow_down_dist(0.0f),
92  _spline_time(0.0f),
93  _spline_time_scale(0.0f),
94  _spline_vel_scaler(0.0f),
95  _yaw(0.0f)
96 {
98 
99  // init flags
100  _flags.reached_destination = false;
101  _flags.fast_waypoint = false;
102  _flags.slowing_down = false;
103  _flags.recalc_wp_leash = false;
104  _flags.new_wp_destination = false;
106 
107  // sanity check some parameters
109  _wp_radius_cm = MAX(_wp_radius_cm, WPNAV_WP_RADIUS_MIN);
110 }
111 
112 
114 void AC_WPNav::init_brake_target(float accel_cmss)
115 {
116  const Vector3f& curr_vel = _inav.get_velocity();
117  Vector3f stopping_point;
118 
119  // initialise position controller
123 
124  // initialise pos controller speed and acceleration
125  _pos_control.set_speed_xy(curr_vel.length());
126  _pos_control.set_accel_xy(accel_cmss);
128 
129  // set target position
130  _pos_control.get_stopping_point_xy(stopping_point);
131  _pos_control.set_xy_target(stopping_point.x, stopping_point.y);
132 }
133 
134 // update_brake - run the stop controller - gets called at 400hz
135 void AC_WPNav::update_brake(float ekfGndSpdLimit, float ekfNavVelGainScaler)
136 {
137  // send adjusted feed forward velocity back to position controller
139  _pos_control.update_xy_controller(ekfNavVelGainScaler);
140 }
141 
145 
150 {
151  // check _wp_accel_cmss is reasonable
152  if (_wp_accel_cmss <= 0) {
153  _wp_accel_cmss.set_and_save(WPNAV_ACCELERATION);
154  }
155 
156  // initialise position controller
160 
161  // initialise feed forward velocity to zero
163 
164  // initialise position controller speed and acceleration
171 
172  // initialise yaw heading to current heading target
173  _flags.wp_yaw_set = false;
174 }
175 
177 void AC_WPNav::set_speed_xy(float speed_cms)
178 {
179  // range check new target speed and update position controller
180  if (speed_cms >= WPNAV_WP_SPEED_MIN) {
181  _wp_speed_cms = speed_cms;
183  // flag that wp leash must be recalculated
184  _flags.recalc_wp_leash = true;
185  }
186 }
187 
191 {
192  bool terr_alt;
193  Vector3f dest_neu;
194 
195  // convert destination location to vector
196  if (!get_vector_NEU(destination, dest_neu, terr_alt)) {
197  return false;
198  }
199 
200  // set target as vector from EKF origin
201  return set_wp_destination(dest_neu, terr_alt);
202 }
203 
205  Vector3f dest = get_wp_destination();
206  if (!AP::ahrs().get_origin(destination)) {
207  return false;
208  }
209  destination.offset(dest.x*0.01f, dest.y*0.01f);
210  destination.alt += dest.z;
211  return true;
212 }
213 
216 bool AC_WPNav::set_wp_destination(const Vector3f& destination, bool terrain_alt)
217 {
218  Vector3f origin;
219 
220  // if waypoint controller is active use the existing position target as the origin
221  if ((AP_HAL::millis() - _wp_last_update) < 1000) {
222  origin = _pos_control.get_pos_target();
223  } else {
224  // if waypoint controller is not active, set origin to reasonable stopping point (using curr pos and velocity)
227  }
228 
229  // convert origin to alt-above-terrain
230  if (terrain_alt) {
231  float origin_terr_offset;
232  if (!get_terrain_offset(origin_terr_offset)) {
233  return false;
234  }
235  origin.z -= origin_terr_offset;
236  }
237 
238  // set origin and destination
239  return set_wp_origin_and_destination(origin, destination, terrain_alt);
240 }
241 
243 bool AC_WPNav::set_wp_destination_NED(const Vector3f& destination_NED)
244 {
245  // convert NED to NEU and do not use terrain following
246  return set_wp_destination(Vector3f(destination_NED.x * 100.0f, destination_NED.y * 100.0f, -destination_NED.z * 100.0f), false);
247 }
248 
252 bool AC_WPNav::set_wp_origin_and_destination(const Vector3f& origin, const Vector3f& destination, bool terrain_alt)
253 {
254  // store origin and destination locations
255  _origin = origin;
256  _destination = destination;
257  _terrain_alt = terrain_alt;
258  Vector3f pos_delta = _destination - _origin;
259 
260  _track_length = pos_delta.length(); // get track length
261  _track_length_xy = safe_sqrt(sq(pos_delta.x)+sq(pos_delta.y)); // get horizontal track length (used to decide if we should update yaw)
262 
263  // calculate each axis' percentage of the total distance to the destination
264  if (is_zero(_track_length)) {
265  // avoid possible divide by zero
266  _pos_delta_unit.x = 0;
267  _pos_delta_unit.y = 0;
268  _pos_delta_unit.z = 0;
269  }else{
270  _pos_delta_unit = pos_delta/_track_length;
271  }
272 
273  // calculate leash lengths
275 
276  // get origin's alt-above-terrain
277  float origin_terr_offset = 0.0f;
278  if (terrain_alt) {
279  if (!get_terrain_offset(origin_terr_offset)) {
280  return false;
281  }
282  }
283 
284  // initialise intermediate point to the origin
285  _pos_control.set_pos_target(origin + Vector3f(0,0,origin_terr_offset));
286  _track_desired = 0; // target is at beginning of track
287  _flags.reached_destination = false;
288  _flags.fast_waypoint = false; // default waypoint back to slow
289  _flags.slowing_down = false; // target is not slowing down yet
291  _flags.new_wp_destination = true; // flag new waypoint so we can freeze the pos controller's feed forward and smooth the transition
292  _flags.wp_yaw_set = false;
293 
294  // initialise the limited speed to current speed along the track
295  const Vector3f &curr_vel = _inav.get_velocity();
296  // get speed along track (note: we convert vertical speed into horizontal speed equivalent)
297  float speed_along_track = curr_vel.x * _pos_delta_unit.x + curr_vel.y * _pos_delta_unit.y + curr_vel.z * _pos_delta_unit.z;
298  _limited_speed_xy_cms = constrain_float(speed_along_track,0,_wp_speed_cms);
299 
300  return true;
301 }
302 
307 {
308  // return immediately if vehicle is not at the origin
309  if (_track_desired > 0.0f) {
310  return;
311  }
312 
313  // get current and target locations
314  const Vector3f curr_pos = _inav.get_position();
315  const Vector3f pos_target = _pos_control.get_pos_target();
316 
317  // calculate difference between current position and target
318  Vector3f pos_diff = curr_pos - pos_target;
319 
320  // shift origin and destination
321  _origin += pos_diff;
322  _destination += pos_diff;
323 
324  // move pos controller target and disable feed forward
325  _pos_control.set_pos_target(curr_pos);
327 }
328 
330 void AC_WPNav::get_wp_stopping_point_xy(Vector3f& stopping_point) const
331 {
332  _pos_control.get_stopping_point_xy(stopping_point);
333 }
334 
336 void AC_WPNav::get_wp_stopping_point(Vector3f& stopping_point) const
337 {
338  _pos_control.get_stopping_point_xy(stopping_point);
339  _pos_control.get_stopping_point_z(stopping_point);
340 }
341 
344 {
345  float track_covered; // distance (in cm) along the track that the vehicle has traveled. Measured by drawing a perpendicular line from the track to the vehicle.
346  Vector3f track_error; // distance error (in cm) from the track_covered position (i.e. closest point on the line to the vehicle) and the vehicle
347  float track_desired_max; // the farthest distance (in cm) along the track that the leash will allow
348  float track_leash_slack; // additional distance (in cm) along the track from our track_covered position that our leash will allow
349  bool reached_leash_limit = false; // true when track has reached leash limit and we need to slow down the target point
350 
351  // get current location
352  Vector3f curr_pos = _inav.get_position();
353 
354  // calculate terrain adjustments
355  float terr_offset = 0.0f;
356  if (_terrain_alt && !get_terrain_offset(terr_offset)) {
357  return false;
358  }
359 
360  // calculate 3d vector from segment's origin
361  Vector3f curr_delta = (curr_pos - Vector3f(0,0,terr_offset)) - _origin;
362 
363  // calculate how far along the track we are
364  track_covered = curr_delta.x * _pos_delta_unit.x + curr_delta.y * _pos_delta_unit.y + curr_delta.z * _pos_delta_unit.z;
365 
366  // calculate the point closest to the vehicle on the segment from origin to destination
367  Vector3f track_covered_pos = _pos_delta_unit * track_covered;
368 
369  // calculate the distance vector from the vehicle to the closest point on the segment from origin to destination
370  track_error = curr_delta - track_covered_pos;
371 
372  // calculate the horizontal error
373  float track_error_xy = norm(track_error.x, track_error.y);
374 
375  // calculate the vertical error
376  float track_error_z = fabsf(track_error.z);
377 
378  // get up leash if we are moving up, down leash if we are moving down
379  float leash_z = track_error.z >= 0 ? _pos_control.get_leash_up_z() : _pos_control.get_leash_down_z();
380 
381  // use pythagoras's theorem calculate how far along the track we could move the intermediate target before reaching the end of the leash
382  // track_desired_max is the distance from the vehicle to our target point along the track. It is the "hypotenuse" which we want to be no longer than our leash (aka _track_leash_length)
383  // track_error is the line from the vehicle to the closest point on the track. It is the "opposite" side
384  // track_leash_slack is the line from the closest point on the track to the target point. It is the "adjacent" side. We adjust this so the track_desired_max is no longer than the leash
385  float track_leash_length_abs = fabsf(_track_leash_length);
386  float track_error_max_abs = MAX(_track_leash_length*track_error_z/leash_z, _track_leash_length*track_error_xy/_pos_control.get_leash_xy());
387  track_leash_slack = (track_leash_length_abs > track_error_max_abs) ? safe_sqrt(sq(_track_leash_length) - sq(track_error_max_abs)) : 0;
388  track_desired_max = track_covered + track_leash_slack;
389 
390  // check if target is already beyond the leash
391  if (_track_desired > track_desired_max) {
392  reached_leash_limit = true;
393  }
394 
395  // get current velocity
396  const Vector3f &curr_vel = _inav.get_velocity();
397  // get speed along track
398  float speed_along_track = curr_vel.x * _pos_delta_unit.x + curr_vel.y * _pos_delta_unit.y + curr_vel.z * _pos_delta_unit.z;
399 
400  // calculate point at which velocity switches from linear to sqrt
401  float linear_velocity = _wp_speed_cms;
402  float kP = _pos_control.get_pos_xy_p().kP();
403  if (kP >= 0.0f) { // avoid divide by zero
404  linear_velocity = _track_accel/kP;
405  }
406 
407  // let the limited_speed_xy_cms be some range above or below current velocity along track
408  if (speed_along_track < -linear_velocity) {
409  // we are traveling fast in the opposite direction of travel to the waypoint so do not move the intermediate point
411  }else{
412  // increase intermediate target point's velocity if not yet at the leash limit
413  if(dt > 0 && !reached_leash_limit) {
414  _limited_speed_xy_cms += 2.0f * _track_accel * dt;
415  }
416  // do not allow speed to be below zero or over top speed
418 
419  // check if we should begin slowing down
420  if (!_flags.fast_waypoint) {
421  float dist_to_dest = _track_length - _track_desired;
422  if (!_flags.slowing_down && dist_to_dest <= _slow_down_dist) {
423  _flags.slowing_down = true;
424  }
425  // if target is slowing down, limit the speed
426  if (_flags.slowing_down) {
428  }
429  }
430 
431  // if our current velocity is within the linear velocity range limit the intermediate point's velocity to be no more than the linear_velocity above or below our current velocity
432  if (fabsf(speed_along_track) < linear_velocity) {
433  _limited_speed_xy_cms = constrain_float(_limited_speed_xy_cms,speed_along_track-linear_velocity,speed_along_track+linear_velocity);
434  }
435  }
436  // advance the current target
437  if (!reached_leash_limit) {
439 
440  // reduce speed if we reach end of leash
441  if (_track_desired > track_desired_max) {
442  _track_desired = track_desired_max;
443  _limited_speed_xy_cms -= 2.0f * _track_accel * dt;
444  if (_limited_speed_xy_cms < 0.0f) {
445  _limited_speed_xy_cms = 0.0f;
446  }
447  }
448  }
449 
450  // do not let desired point go past the end of the track unless it's a fast waypoint
451  if (!_flags.fast_waypoint) {
453  } else {
455  }
456 
457  // recalculate the desired position
458  Vector3f final_target = _origin + _pos_delta_unit * _track_desired;
459  // convert final_target.z to altitude above the ekf origin
460  final_target.z += terr_offset;
461  _pos_control.set_pos_target(final_target);
462 
463  // check if we've reached the waypoint
464  if( !_flags.reached_destination ) {
465  if( _track_desired >= _track_length ) {
466  // "fast" waypoints are complete once the intermediate point reaches the destination
467  if (_flags.fast_waypoint) {
469  }else{
470  // regular waypoints also require the copter to be within the waypoint radius
471  Vector3f dist_to_dest = (curr_pos - Vector3f(0,0,terr_offset)) - _destination;
472  if( dist_to_dest.length() <= _wp_radius_cm ) {
474  }
475  }
476  }
477  }
478 
479  // update the target yaw if origin and destination are at least 2m apart horizontally
482  // if the leash is short (i.e. moving slowly) and destination is at least 2m horizontally, point along the segment from origin to destination
484  } else {
485  Vector3f horiz_leash_xy = final_target - curr_pos;
486  horiz_leash_xy.z = 0;
488  set_yaw_cd(RadiansToCentiDegrees(atan2f(horiz_leash_xy.y,horiz_leash_xy.x)));
489  }
490  }
491  }
492 
493  // successfully advanced along track
494  return true;
495 }
496 
499 {
500  // get current location
501  Vector3f curr = _inav.get_position();
502  return norm(_destination.x-curr.x,_destination.y-curr.y);
503 }
504 
507 {
509 }
510 
513 {
514  bool ret = true;
515 
516  // calculate dt
518  if (dt >= 0.2f) {
519  dt = 0.0f;
520  }
521 
522  // allow the accel and speed values to be set without changing
523  // out of auto mode. This makes it easier to tune auto flight
526 
527  // advance the target if necessary
529  // To-Do: handle inability to advance along track (probably because of missing terrain data)
530  ret = false;
531  }
532 
533  // freeze feedforwards during known discontinuities
535  _flags.new_wp_destination = false;
537  }
538 
541 
543 
544  return ret;
545 }
546 
547 // check_wp_leash_length - check if waypoint leash lengths need to be recalculated
548 // should be called after _pos_control.update_xy_controller which may have changed the position controller leash lengths
550 {
551  // exit immediately if recalc is not required
552  if (_flags.recalc_wp_leash) {
554  }
555 }
556 
559 {
560  // length of the unit direction vector in the horizontal
561  float pos_delta_unit_xy = norm(_pos_delta_unit.x, _pos_delta_unit.y);
562  float pos_delta_unit_z = fabsf(_pos_delta_unit.z);
563 
564  float speed_z;
565  float leash_z;
566  if (_pos_delta_unit.z >= 0.0f) {
567  speed_z = _wp_speed_up_cms;
568  leash_z = _pos_control.get_leash_up_z();
569  }else{
570  speed_z = _wp_speed_down_cms;
571  leash_z = _pos_control.get_leash_down_z();
572  }
573 
574  // calculate the maximum acceleration, maximum velocity, and leash length in the direction of travel
575  if(is_zero(pos_delta_unit_z) && is_zero(pos_delta_unit_xy)){
576  _track_accel = 0;
577  _track_speed = 0;
579  }else if(is_zero(_pos_delta_unit.z)){
580  _track_accel = _wp_accel_cmss/pos_delta_unit_xy;
581  _track_speed = _wp_speed_cms/pos_delta_unit_xy;
582  _track_leash_length = _pos_control.get_leash_xy()/pos_delta_unit_xy;
583  }else if(is_zero(pos_delta_unit_xy)){
584  _track_accel = _wp_accel_z_cmss/pos_delta_unit_z;
585  _track_speed = speed_z/pos_delta_unit_z;
586  _track_leash_length = leash_z/pos_delta_unit_z;
587  }else{
588  _track_accel = MIN(_wp_accel_z_cmss/pos_delta_unit_z, _wp_accel_cmss/pos_delta_unit_xy);
589  _track_speed = MIN(speed_z/pos_delta_unit_z, _wp_speed_cms/pos_delta_unit_xy);
590  _track_leash_length = MIN(leash_z/pos_delta_unit_z, _pos_control.get_leash_xy()/pos_delta_unit_xy);
591  }
592 
593  // calculate slow down distance (the distance from the destination when the target point should begin to slow down)
595 
596  // set recalc leash flag to false
597  _flags.recalc_wp_leash = false;
598 }
599 
600 // returns target yaw in centi-degrees (used for wp and spline navigation)
601 float AC_WPNav::get_yaw() const
602 {
603  if (_flags.wp_yaw_set) {
604  return _yaw;
605  } else {
606  // if yaw has not been set return attitude controller's current target
608  }
609 }
610 
611 // set heading used for spline and waypoint navigation
612 void AC_WPNav::set_yaw_cd(float heading_cd)
613 {
614  _yaw = heading_cd;
615  _flags.wp_yaw_set = true;
616 }
617 
621 
627 bool AC_WPNav::set_spline_destination(const Location_Class& destination, bool stopped_at_start, spline_segment_end_type seg_end_type, Location_Class next_destination)
628 {
629  // convert destination location to vector
630  Vector3f dest_neu;
631  bool dest_terr_alt;
632  if (!get_vector_NEU(destination, dest_neu, dest_terr_alt)) {
633  return false;
634  }
635 
636  // make altitude frames consistent
637  if (!next_destination.change_alt_frame(destination.get_alt_frame())) {
638  return false;
639  }
640 
641  // convert next destination to vector
642  Vector3f next_dest_neu;
643  bool next_dest_terr_alt;
644  if (!get_vector_NEU(next_destination, next_dest_neu, next_dest_terr_alt)) {
645  return false;
646  }
647 
648  // set target as vector from EKF origin
649  return set_spline_destination(dest_neu, dest_terr_alt, stopped_at_start, seg_end_type, next_dest_neu);
650 }
651 
658 bool AC_WPNav::set_spline_destination(const Vector3f& destination, bool terrain_alt, bool stopped_at_start, spline_segment_end_type seg_end_type, const Vector3f& next_destination)
659 {
660  Vector3f origin;
661 
662  // if waypoint controller is active and copter has reached the previous waypoint use current pos target as the origin
663  if ((AP_HAL::millis() - _wp_last_update) < 1000) {
664  origin = _pos_control.get_pos_target();
665  }else{
666  // otherwise calculate origin from the current position and velocity
669  }
670 
671  // convert origin to alt-above-terrain
672  if (terrain_alt) {
673  float terr_offset;
674  if (!get_terrain_offset(terr_offset)) {
675  return false;
676  }
677  origin.z -= terr_offset;
678  }
679 
680  // set origin and destination
681  return set_spline_origin_and_destination(origin, destination, terrain_alt, stopped_at_start, seg_end_type, next_destination);
682 }
683 
687 bool AC_WPNav::set_spline_origin_and_destination(const Vector3f& origin, const Vector3f& destination, bool terrain_alt, bool stopped_at_start, spline_segment_end_type seg_end_type, const Vector3f& next_destination)
688 {
689  // mission is "active" if wpnav has been called recently and vehicle reached the previous waypoint
690  bool prev_segment_exists = (_flags.reached_destination && ((AP_HAL::millis() - _wp_last_update) < 1000));
691 
693  if (dt >= 0.2f) {
694  dt = 0.0f;
695  }
696 
697  // check _wp_accel_cmss is reasonable to avoid divide by zero
698  if (_wp_accel_cmss <= 0) {
699  _wp_accel_cmss.set_and_save(WPNAV_ACCELERATION);
700  }
701 
702  // segment start types
703  // stop - vehicle is not moving at origin
704  // straight-fast - vehicle is moving, previous segment is straight. vehicle will fly straight through the waypoint before beginning it's spline path to the next wp
705  // _flag.segment_type holds whether prev segment is straight vs spline but we don't know if it has a delay
706  // spline-fast - vehicle is moving, previous segment is splined, vehicle will fly through waypoint but previous segment should have it flying in the correct direction (i.e. exactly parallel to position difference vector from previous segment's origin to this segment's destination)
707 
708  // calculate spline velocity at origin
709  if (stopped_at_start || !prev_segment_exists) {
710  // if vehicle is stopped at the origin, set origin velocity to 0.02 * distance vector from origin to destination
711  _spline_origin_vel = (destination - origin) * dt;
712  _spline_time = 0.0f;
713  _spline_vel_scaler = 0.0f;
714  }else{
715  // look at previous segment to determine velocity at origin
717  // previous segment is straight, vehicle is moving so vehicle should fly straight through the origin
718  // before beginning it's spline path to the next waypoint. Note: we are using the previous segment's origin and destination
720  _spline_time = 0.0f; // To-Do: this should be set based on how much overrun there was from straight segment?
721  _spline_vel_scaler = _pos_control.get_vel_target().length(); // start velocity target from current target velocity
722  }else{
723  // previous segment is splined, vehicle will fly through origin
724  // we can use the previous segment's destination velocity as this segment's origin velocity
725  // Note: previous segment will leave destination velocity parallel to position difference vector
726  // from previous segment's origin to this segment's destination)
728  if (_spline_time > 1.0f && _spline_time < 1.1f) { // To-Do: remove hard coded 1.1f
729  _spline_time -= 1.0f;
730  }else{
731  _spline_time = 0.0f;
732  }
733  // Note: we leave _spline_vel_scaler as it was from end of previous segment
734  }
735  }
736 
737  // calculate spline velocity at destination
738  switch (seg_end_type) {
739 
740  case SEGMENT_END_STOP:
741  // if vehicle stops at the destination set destination velocity to 0.02 * distance vector from origin to destination
742  _spline_destination_vel = (destination - origin) * dt;
743  _flags.fast_waypoint = false;
744  break;
745 
747  // if next segment is straight, vehicle's final velocity should face along the next segment's position
748  _spline_destination_vel = (next_destination - destination);
749  _flags.fast_waypoint = true;
750  break;
751 
752  case SEGMENT_END_SPLINE:
753  // if next segment is splined, vehicle's final velocity should face parallel to the line from the origin to the next destination
754  _spline_destination_vel = (next_destination - origin);
755  _flags.fast_waypoint = true;
756  break;
757  }
758 
759  // code below ensures we don't get too much overshoot when the next segment is short
761  float pos_len = (destination - origin).length() * 4.0f;
762  if (vel_len > pos_len) {
763  // if total start+stop velocity is more than twice position difference
764  // use a scaled down start and stop velocityscale the start and stop velocities down
765  float vel_scaling = pos_len / vel_len;
766  // update spline calculator
767  update_spline_solution(origin, destination, _spline_origin_vel * vel_scaling, _spline_destination_vel * vel_scaling);
768  }else{
769  // update spline calculator
771  }
772 
773  // store origin and destination locations
774  _origin = origin;
775  _destination = destination;
776  _terrain_alt = terrain_alt;
777 
778  // calculate slow down distance
780 
781  // get alt-above-terrain
782  float terr_offset = 0.0f;
783  if (terrain_alt) {
784  if (!get_terrain_offset(terr_offset)) {
785  return false;
786  }
787  }
788 
789  // initialise intermediate point to the origin
790  _pos_control.set_pos_target(origin + Vector3f(0,0,terr_offset));
791  _flags.reached_destination = false;
793  _flags.new_wp_destination = true; // flag new waypoint so we can freeze the pos controller's feed forward and smooth the transition
794  _flags.wp_yaw_set = false;
795 
796  // initialise yaw related variables
797  _track_length_xy = safe_sqrt(sq(_destination.x - _origin.x)+sq(_destination.y - _origin.y)); // horizontal track length (used to decide if we should update yaw)
798 
799  return true;
800 }
801 
804 {
805  // exit immediately if this is not a spline segment
807  return false;
808  }
809 
810  bool ret = true;
811 
812  // calculate dt
814  if (dt >= 0.2f) {
815  dt = 0.0f;
816  }
817 
818  // advance the target if necessary
820  // To-Do: handle failure to advance along track (due to missing terrain data)
821  ret = false;
822  }
823 
824  // freeze feedforwards during known discontinuities
826  _flags.new_wp_destination = false;
828  }
829 
830  // run horizontal position controller
832 
834 
835  return ret;
836 }
837 
840 void AC_WPNav::update_spline_solution(const Vector3f& origin, const Vector3f& dest, const Vector3f& origin_vel, const Vector3f& dest_vel)
841 {
842  _hermite_spline_solution[0] = origin;
843  _hermite_spline_solution[1] = origin_vel;
844  _hermite_spline_solution[2] = -origin*3.0f -origin_vel*2.0f + dest*3.0f - dest_vel;
845  _hermite_spline_solution[3] = origin*2.0f + origin_vel -dest*2.0f + dest_vel;
846  }
847 
850 {
852  Vector3f target_pos, target_vel;
853 
854  // update target position and velocity from spline calculator
855  calc_spline_pos_vel(_spline_time, target_pos, target_vel);
856 
857  // if target velocity is zero the origin and destination must be the same
858  // so flag reached destination (and protect against divide by zero)
859  float target_vel_length = target_vel.length();
860  if (is_zero(target_vel_length)) {
862  return true;
863  }
864 
865  _pos_delta_unit = target_vel / target_vel_length;
867 
868  // get current location
869  Vector3f curr_pos = _inav.get_position();
870 
871  // get terrain altitude offset for origin and current position (i.e. change in terrain altitude from a position vs ekf origin)
872  float terr_offset = 0.0f;
873  if (_terrain_alt && !get_terrain_offset(terr_offset)) {
874  return false;
875  }
876 
877  // calculate position error
878  Vector3f track_error = curr_pos - target_pos;
879  track_error.z -= terr_offset;
880 
881  // calculate the horizontal error
882  float track_error_xy = norm(track_error.x, track_error.y);
883 
884  // calculate the vertical error
885  float track_error_z = fabsf(track_error.z);
886 
887  // get position control leash lengths
888  float leash_xy = _pos_control.get_leash_xy();
889  float leash_z;
890  if (track_error.z >= 0) {
891  leash_z = _pos_control.get_leash_up_z();
892  }else{
893  leash_z = _pos_control.get_leash_down_z();
894  }
895 
896  // calculate how far along the track we could move the intermediate target before reaching the end of the leash
897  float track_leash_slack = MIN(_track_leash_length*(leash_z-track_error_z)/leash_z, _track_leash_length*(leash_xy-track_error_xy)/leash_xy);
898  if (track_leash_slack < 0.0f) {
899  track_leash_slack = 0.0f;
900  }
901 
902  // update velocity
903  float spline_dist_to_wp = (_destination - target_pos).length();
904  float vel_limit = _wp_speed_cms;
905  if (!is_zero(dt)) {
906  vel_limit = MIN(vel_limit, track_leash_slack/dt);
907  }
908 
909  // if within the stopping distance from destination, set target velocity to sqrt of distance * 2 * acceleration
910  if (!_flags.fast_waypoint && spline_dist_to_wp < _slow_down_dist) {
911  _spline_vel_scaler = safe_sqrt(spline_dist_to_wp * 2.0f * _wp_accel_cmss);
912  }else if(_spline_vel_scaler < vel_limit) {
913  // increase velocity using acceleration
915  }
916 
917  // constrain target velocity
919 
920  // scale the spline_time by the velocity we've calculated vs the velocity that came out of the spline calculator
921  _spline_time_scale = _spline_vel_scaler / target_vel_length;
922 
923  // update target position
924  target_pos.z += terr_offset;
925  _pos_control.set_pos_target(target_pos);
926 
927  // update the target yaw if origin and destination are at least 2m apart horizontally
930  // if the leash is very short (i.e. flying at low speed) use the target point's velocity along the track
931  if (!is_zero(target_vel.x) && !is_zero(target_vel.y)) {
932  set_yaw_cd(RadiansToCentiDegrees(atan2f(target_vel.y,target_vel.x)));
933  }
934  } else {
935  // point vehicle along the leash (i.e. point vehicle towards target point on the segment from origin to destination)
936  float track_error_xy_length = safe_sqrt(sq(track_error.x)+sq(track_error.y));
937  if (track_error_xy_length > MIN(WPNAV_YAW_DIST_MIN, _pos_control.get_leash_xy()*WPNAV_YAW_LEASH_PCT_MIN)) {
938  // To-Do: why is track_error sign reversed?
939  set_yaw_cd(RadiansToCentiDegrees(atan2f(-track_error.y,-track_error.x)));
940  }
941  }
942  }
943 
944  // advance spline time to next step
946 
947  // we will reach the next waypoint in the next step so set reached_destination flag
948  // To-Do: is this one step too early?
949  if (_spline_time >= 1.0f) {
951  }
952  }
953  return true;
954 }
955 
956 // calc_spline_pos_vel_accel - calculates target position, velocity and acceleration for the given "spline_time"
958 void AC_WPNav::calc_spline_pos_vel(float spline_time, Vector3f& position, Vector3f& velocity)
959 {
960  float spline_time_sqrd = spline_time * spline_time;
961  float spline_time_cubed = spline_time_sqrd * spline_time;
962 
963  position = _hermite_spline_solution[0] + \
964  _hermite_spline_solution[1] * spline_time + \
965  _hermite_spline_solution[2] * spline_time_sqrd + \
966  _hermite_spline_solution[3] * spline_time_cubed;
967 
968  velocity = _hermite_spline_solution[1] + \
969  _hermite_spline_solution[2] * 2.0f * spline_time + \
970  _hermite_spline_solution[3] * 3.0f * spline_time_sqrd;
971 }
972 
973 // get terrain's altitude (in cm above the ekf origin) at the current position (+ve means terrain below vehicle is above ekf origin's altitude)
974 bool AC_WPNav::get_terrain_offset(float& offset_cm)
975 {
976 #if AP_TERRAIN_AVAILABLE
977  // use range finder if connected
979  if (_rangefinder_healthy) {
980  offset_cm = _inav.get_altitude() - _rangefinder_alt_cm;
981  return true;
982  } else {
983  return false;
984  }
985  }
986 
987  // use terrain database
988  float terr_alt = 0.0f;
989  if (_terrain != nullptr && _terrain->height_above_terrain(terr_alt, true)) {
990  offset_cm = _inav.get_altitude() - (terr_alt * 100.0f);
991  return true;
992  }
993 #endif
994  return false;
995 }
996 
997 // convert location to vector from ekf origin. terrain_alt is set to true if resulting vector's z-axis should be treated as alt-above-terrain
998 // returns false if conversion failed (likely because terrain data was not available)
999 bool AC_WPNav::get_vector_NEU(const Location_Class &loc, Vector3f &vec, bool &terrain_alt)
1000 {
1001  // convert location to NE vector2f
1002  Vector2f res_vec;
1003  if (!loc.get_vector_xy_from_origin_NE(res_vec)) {
1004  return false;
1005  }
1006 
1007  // convert altitude
1009  int32_t terr_alt;
1011  return false;
1012  }
1013  vec.z = terr_alt;
1014  terrain_alt = true;
1015  } else {
1016  terrain_alt = false;
1017  int32_t temp_alt;
1018  if (!loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_ORIGIN, temp_alt)) {
1019  return false;
1020  }
1021  vec.z = temp_alt;
1022  terrain_alt = false;
1023  }
1024 
1025  // copy xy (we do this to ensure we do not adjust vector unless the overall conversion is successful
1026  vec.x = res_vec.x;
1027  vec.y = res_vec.y;
1028 
1029  return true;
1030 }
1031 
1035 
1037 void AC_WPNav::calc_slow_down_distance(float speed_cms, float accel_cmss)
1038 {
1039  // protect against divide by zero
1040  if (accel_cmss <= 0.0f) {
1041  _slow_down_dist = 0.0f;
1042  return;
1043  }
1044  // To-Do: should we use a combination of horizontal and vertical speeds?
1045  // To-Do: update this automatically when speed or acceleration is changed
1046  _slow_down_dist = speed_cms * speed_cms / (4.0f*accel_cmss);
1047 }
1048 
1050 float AC_WPNav::get_slow_down_speed(float dist_from_dest_cm, float accel_cmss)
1051 {
1052  // return immediately if distance is zero (or less)
1053  if (dist_from_dest_cm <= 0) {
1054  return WPNAV_WP_TRACK_SPEED_MIN;
1055  }
1056 
1057  // calculate desired speed near destination
1058  float target_speed = safe_sqrt(dist_from_dest_cm * 4.0f * accel_cmss);
1059 
1060  // ensure desired speed never becomes too low
1061  if (target_speed < WPNAV_WP_TRACK_SPEED_MIN) {
1062  return WPNAV_WP_TRACK_SPEED_MIN;
1063  } else {
1064  return target_speed;
1065  }
1066 }
float _track_leash_length
Definition: AC_WPNav.h:292
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
void set_speed_xy(float speed_cms)
set_speed_xy - allows main code to pass target horizontal velocity for wp navigation ...
Definition: AC_WPNav.cpp:177
const AC_AttitudeControl & _attitude_control
Definition: AC_WPNav.h:268
void get_stopping_point_xy(Vector3f &stopping_point) const
void check_wp_leash_length()
Definition: AC_WPNav.cpp:549
#define WPNAV_WP_TRACK_SPEED_MIN
Definition: AC_WPNav.h:19
void set_desired_velocity_xy(float vel_lat_cms, float vel_lon_cms)
bool get_terrain_offset(float &offset_cm)
Definition: AC_WPNav.cpp:974
AP_Float _wp_radius_cm
Definition: AC_WPNav.h:276
Vector3< float > Vector3f
Definition: vector3.h:246
float get_slow_down_speed(float dist_from_dest_cm, float accel_cmss)
get_slow_down_speed - returns target speed of target point based on distance from the destination (in...
Definition: AC_WPNav.cpp:1050
void calc_slow_down_distance(float speed_cms, float accel_cmss)
calc_slow_down_distance - calculates distance before waypoint that target point should begin to slow-...
Definition: AC_WPNav.cpp:1037
void set_yaw_cd(float heading_cd)
Definition: AC_WPNav.cpp:612
virtual const Vector3f & get_position() const =0
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
Vector3f _origin
Definition: AC_WPNav.h:283
float _yaw
Definition: AC_WPNav.h:302
spline_segment_end_type
Definition: AC_WPNav.h:42
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
const Vector3f & get_vel_target() const
accessors for reporting
float get_yaw() const
Definition: AC_WPNav.cpp:601
Vector3f _pos_delta_unit
Definition: AC_WPNav.h:285
Vector3f _spline_origin_vel
Definition: AC_WPNav.h:298
bool set_spline_destination(const Location_Class &destination, bool stopped_at_start, spline_segment_end_type seg_end_type, Location_Class next_destination)
Definition: AC_WPNav.cpp:627
AC_P & get_pos_xy_p()
void get_stopping_point_z(Vector3f &stopping_point) const
get_stopping_point_z - calculates stopping point based on current position, velocity, vehicle acceleration
AC_WPNav(const AP_InertialNav &inav, const AP_AHRS_View &ahrs, AC_PosControl &pos_control, const AC_AttitudeControl &attitude_control)
Constructor.
Definition: AC_WPNav.cpp:77
#define ToRad(x)
Definition: AP_Common.h:53
bool _rangefinder_available
Definition: AC_WPNav.h:307
void clear_desired_velocity_ff_z()
float _spline_vel_scaler
Definition: AC_WPNav.h:301
void calc_spline_pos_vel(float spline_time, Vector3f &position, Vector3f &velocity)
relies on update_spline_solution being called when the segment&#39;s origin and destination were set ...
Definition: AC_WPNav.cpp:958
void get_wp_stopping_point(Vector3f &stopping_point) const
get_wp_stopping_point - returns vector to stopping point based on 3D position and velocity ...
Definition: AC_WPNav.cpp:336
void set_desired_accel_xy(float accel_lat_cms, float accel_lon_cms)
#define WPNAV_WP_SPEED_MIN
Definition: AC_WPNav.h:18
bool update_spline()
update_spline - update spline controller
Definition: AC_WPNav.cpp:803
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float _limited_speed_xy_cms
Definition: AC_WPNav.h:289
bool advance_spline_target_along_track(float dt)
advance_spline_target_along_track - move target location along track from origin to destination ...
Definition: AC_WPNav.cpp:849
float get_leash_up_z() const
void update_xy_controller(float ekfNavVelGainScaler)
update_xy_controller - run the horizontal position controller - should be called at 100hz or higher ...
float _spline_time_scale
Definition: AC_WPNav.h:297
#define WPNAV_WP_ACCEL_Z_DEFAULT
Definition: AC_WPNav.h:26
const AP_InertialNav & _inav
Definition: AC_WPNav.h:265
#define WPNAV_YAW_DIST_MIN
Definition: AC_WPNav.h:32
float _track_accel
Definition: AC_WPNav.h:290
#define WPNAV_LEASH_LENGTH_MIN
Definition: AC_WPNav.h:28
void init_brake_target(float accel_cmss)
init_brake_target - initializes stop position from current position and velocity
Definition: AC_WPNav.cpp:114
Vector3f _spline_destination_vel
Definition: AC_WPNav.h:299
void update_spline_solution(const Vector3f &origin, const Vector3f &dest, const Vector3f &origin_vel, const Vector3f &dest_vel)
spline protected functions
Definition: AC_WPNav.cpp:840
bool set_wp_destination(const Location_Class &destination)
Definition: AC_WPNav.cpp:190
#define MIN(a, b)
Definition: usb_conf.h:215
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:56
#define WPNAV_WP_RADIUS
Definition: AC_WPNav.h:20
int32_t get_wp_bearing_to_destination() const
get_bearing_to_destination - get bearing to next waypoint in centi-degrees
Definition: AC_WPNav.cpp:506
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
void set_xy_target(float x, float y)
set_xy_target in cm from home
#define RadiansToCentiDegrees(x)
Definition: definitions.h:44
#define WPNAV_WP_FAST_OVERSHOOT_MAX
Definition: AC_WPNav.h:30
bool set_spline_origin_and_destination(const Vector3f &origin, const Vector3f &destination, bool terrain_alt, bool stopped_at_start, spline_segment_end_type seg_end_type, const Vector3f &next_destination)
Definition: AC_WPNav.cpp:687
T y
Definition: vector2.h:37
bool update_wpnav()
update_wpnav - run the wp controller - should be called at 100hz or higher
Definition: AC_WPNav.cpp:512
Vector3f _destination
Definition: AC_WPNav.h:284
float lean_angle_max() const
float _track_length
Definition: AC_WPNav.h:286
AP_Float _wp_speed_cms
Definition: AC_WPNav.h:273
float _track_desired
Definition: AC_WPNav.h:288
const Vector3f & get_wp_destination() const
get_wp_destination waypoint using position vector (distance from ekf origin in cm) ...
Definition: AC_WPNav.h:97
const Vector3f & get_pos_target() const
get_pos_target - get target as position vector (from home in cm)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
ALT_FRAME get_alt_frame() const
Definition: Location.cpp:99
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_WPNav.h:214
#define GRAVITY_MSS
Definition: definitions.h:47
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
bool get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
get altitude in desired frame
Definition: Location.cpp:114
#define f(i)
void init_xy_controller(bool reset_I=true)
T y
Definition: vector3.h:67
float get_leash_down_z() const
void set_speed_z(float speed_down, float speed_up)
float get_wp_distance_to_destination() const
get_wp_distance_to_destination - get horizontal distance to destination in cm
Definition: AC_WPNav.cpp:498
uint32_t millis()
Definition: system.cpp:157
bool set_wp_destination_NED(const Vector3f &destination_NED)
set waypoint destination using NED position vector from ekf origin in meters
Definition: AC_WPNav.cpp:243
void calc_leash_length_z()
T z
Definition: vector3.h:67
uint8_t reached_destination
Definition: AC_WPNav.h:226
void offset(float ofs_north, float ofs_east)
Definition: Location.cpp:232
#define WPNAV_WP_SPEED_UP
Definition: AC_WPNav.h:23
bool get_vector_NEU(const Location_Class &loc, Vector3f &vec, bool &terrain_alt)
Definition: AC_WPNav.cpp:999
bool set_wp_origin_and_destination(const Vector3f &origin, const Vector3f &destination, bool terrain_alt=false)
Definition: AC_WPNav.cpp:252
AC_PosControl & _pos_control
Definition: AC_WPNav.h:267
void shift_wp_origin_to_current_pos()
Definition: AC_WPNav.cpp:306
#define WPNAV_WP_SPEED
Definition: AC_WPNav.h:17
void wp_and_spline_init()
Definition: AC_WPNav.cpp:149
void calc_leash_length_xy()
bool _rangefinder_healthy
Definition: AC_WPNav.h:309
void set_accel_z(float accel_cmss)
set_accel_z - set vertical acceleration in cm/s/s
float _spline_time
Definition: AC_WPNav.h:296
bool change_alt_frame(ALT_FRAME desired_frame)
Definition: Location.cpp:88
void set_pos_target(const Vector3f &position)
set_pos_target in cm from home
AP_Int8 _rangefinder_use
Definition: AC_WPNav.h:308
Vector3f _hermite_spline_solution[4]
Definition: AC_WPNav.h:300
float length(void) const
Definition: vector3.cpp:288
AP_Terrain * _terrain
Definition: AC_WPNav.h:269
void freeze_ff_z()
freeze_ff_z - used to stop the feed forward being calculated during a known discontinuity ...
#define WPNAV_WP_RADIUS_MIN
Definition: AC_WPNav.h:21
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
void get_wp_stopping_point_xy(Vector3f &stopping_point) const
get_wp_stopping_point_xy - returns vector to stopping point based on a horizontal position and veloci...
Definition: AC_WPNav.cpp:330
AP_AHRS & ahrs()
Definition: AP_AHRS.cpp:488
bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
Definition: Location.cpp:192
AP_Float _wp_speed_down_cms
Definition: AC_WPNav.h:275
void set_accel_xy(float accel_cmss)
set_accel_xy - set horizontal acceleration in cm/s/s
float _track_length_xy
Definition: AC_WPNav.h:287
uint8_t recalc_wp_leash
Definition: AC_WPNav.h:229
bool _terrain_alt
Definition: AC_WPNav.h:305
uint32_t _wp_last_update
Definition: AC_WPNav.h:281
Vector3f get_att_target_euler_cd() const
#define WPNAV_YAW_LEASH_PCT_MIN
Definition: AC_WPNav.h:33
AP_Float _wp_accel_z_cmss
Definition: AC_WPNav.h:278
void update_brake(float ekfGndSpdLimit, float ekfNavVelGainScaler)
update_brake - run the brake controller - should be called at 400hz
Definition: AC_WPNav.cpp:135
float sq(const T val)
Definition: AP_Math.h:170
float _track_speed
Definition: AC_WPNav.h:291
AP_Float _wp_accel_cmss
Definition: AC_WPNav.h:277
SegmentType segment_type
Definition: AC_WPNav.h:231
AP_Float _wp_speed_up_cms
Definition: AC_WPNav.h:274
void calculate_wp_leash_length()
calculate_wp_leash_length - calculates track speed, acceleration and leash lengths for waypoint contr...
Definition: AC_WPNav.cpp:558
#define WPNAV_ACCELERATION
Definition: AC_WPNav.h:14
float time_since_last_xy_update() const
virtual const Vector3f & get_velocity() const =0
struct AC_WPNav::wpnav_flags _flags
float get_leash_xy() const
#define WPNAV_WP_SPEED_DOWN
Definition: AC_WPNav.h:24
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
uint8_t new_wp_destination
Definition: AC_WPNav.h:230
virtual float get_altitude() const =0
void set_speed_xy(float speed_cms)
set_speed_xy - set horizontal speed maximum in cm/s
AP_Float & kP()
Definition: AC_P.h:58
float _rangefinder_alt_cm
Definition: AC_WPNav.h:310
float _slow_down_dist
Definition: AC_WPNav.h:293
#define AP_GROUPEND
Definition: AP_Param.h:121
bool advance_wp_target_along_track(float dt)
advance_wp_target_along_track - move target location along track from origin to destination ...
Definition: AC_WPNav.cpp:343
T x
Definition: vector3.h:67
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214