APM:Libraries
AC_WPNav.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_Param/AP_Param.h>
5 #include <AP_Math/AP_Math.h>
6 #include <AP_Common/Location.h>
7 #include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library
8 #include <AC_AttitudeControl/AC_PosControl.h> // Position control library
9 #include <AC_AttitudeControl/AC_AttitudeControl.h> // Attitude control library
10 #include <AP_Terrain/AP_Terrain.h>
11 #include <AC_Avoidance/AC_Avoid.h> // Stop at fence library
12 
13 // maximum velocities and accelerations
14 #define WPNAV_ACCELERATION 100.0f // defines the default velocity vs distant curve. maximum acceleration in cm/s/s that position controller asks for from acceleration controller
15 #define WPNAV_ACCELERATION_MIN 50.0f // minimum acceleration in cm/s/s - used for sanity checking _wp_accel parameter
16 
17 #define WPNAV_WP_SPEED 500.0f // default horizontal speed between waypoints in cm/s
18 #define WPNAV_WP_SPEED_MIN 20.0f // minimum horizontal speed between waypoints in cm/s
19 #define WPNAV_WP_TRACK_SPEED_MIN 50.0f // minimum speed along track of the target point the vehicle is chasing in cm/s (used as target slows down before reaching destination)
20 #define WPNAV_WP_RADIUS 200.0f // default waypoint radius in cm
21 #define WPNAV_WP_RADIUS_MIN 10.0f // minimum waypoint radius in cm
22 
23 #define WPNAV_WP_SPEED_UP 250.0f // default maximum climb velocity
24 #define WPNAV_WP_SPEED_DOWN 150.0f // default maximum descent velocity
25 
26 #define WPNAV_WP_ACCEL_Z_DEFAULT 100.0f // default vertical acceleration between waypoints in cm/s/s
27 
28 #define WPNAV_LEASH_LENGTH_MIN 100.0f // minimum leash lengths in cm
29 
30 #define WPNAV_WP_FAST_OVERSHOOT_MAX 200.0f // 2m overshoot is allowed during fast waypoints to allow for smooth transitions to next waypoint
31 
32 #define WPNAV_YAW_DIST_MIN 200 // minimum track length which will lead to target yaw being updated to point at next waypoint. Under this distance the yaw target will be frozen at the current heading
33 #define WPNAV_YAW_LEASH_PCT_MIN 0.134f // target point must be at least this distance from the vehicle (expressed as a percentage of the maximum distance it can be from the vehicle - i.e. the leash length)
34 
35 #define WPNAV_RANGEFINDER_FILT_Z 0.25f // range finder distance filtered at 0.25hz
36 
37 class AC_WPNav
38 {
39 public:
40 
41  // spline segment end types enum
46  };
47 
49  AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control);
50 
52  void set_terrain(AP_Terrain* terrain_ptr) { _terrain = terrain_ptr; }
53 
55  void set_avoidance(AC_Avoid* avoid_ptr) { _avoid = avoid_ptr; }
56 
58  void set_rangefinder_alt(bool use, bool healthy, float alt_cm) { _rangefinder_available = use; _rangefinder_healthy = healthy; _rangefinder_alt_cm = alt_cm; }
59 
64  void init_brake_target(float accel_cmss);
67  void update_brake(float ekfGndSpdLimit, float ekfNavVelGainScaler);
68 
72 
76  void wp_and_spline_init();
77 
79  void set_speed_xy(float speed_cms);
80 
82  float get_speed_xy() const { return _wp_speed_cms; }
83 
85  float get_speed_up() const { return _wp_speed_up_cms; }
86 
88  float get_speed_down() const { return _wp_speed_down_cms; }
89 
91  float get_accel_z() const { return _wp_accel_z_cmss; }
92 
94  float get_wp_acceleration() const { return _wp_accel_cmss.get(); }
95 
97  const Vector3f &get_wp_destination() const { return _destination; }
98 
100  const Vector3f &get_wp_origin() const { return _origin; }
101 
104  bool set_wp_destination(const Location_Class& destination);
105 
106  // returns wp location using location class.
107  // returns false if unable to convert from target vector to global
108  // coordinates
109  bool get_wp_destination(Location_Class& destination);
110 
113  bool set_wp_destination(const Vector3f& destination, bool terrain_alt = false);
114 
116  bool set_wp_destination_NED(const Vector3f& destination_NED);
117 
121  bool set_wp_origin_and_destination(const Vector3f& origin, const Vector3f& destination, bool terrain_alt = false);
122 
127 
130  void get_wp_stopping_point_xy(Vector3f& stopping_point) const;
131  void get_wp_stopping_point(Vector3f& stopping_point) const;
132 
134  float get_wp_distance_to_destination() const;
135 
137  int32_t get_wp_bearing_to_destination() const;
138 
141 
143  void set_fast_waypoint(bool fast) { _flags.fast_waypoint = fast; }
144 
146  bool update_wpnav();
147 
148  // check_wp_leash_length - check recalc_wp_leash flag and calls calculate_wp_leash_length() if necessary
149  // should be called after _pos_control.update_xy_controller which may have changed the position controller leash lengths
150  void check_wp_leash_length();
151 
154 
158 
159  // segment start types
160  // stop - vehicle is not moving at origin
161  // 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
162  // _flag.segment_type holds whether prev segment is straight vs spline but we don't know if it has a delay
163  // 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)
164 
165  // segment end types
166  // stop - vehicle is not moving at destination
167  // straight-fast - next segment is straight, vehicle's destination velocity should be directly along track from this segment's destination to next segment's destination
168  // spline-fast - next segment is spline, vehicle's destination velocity should be parallel to position difference vector from previous segment's origin to this segment's destination
169 
170  // get target yaw in centi-degrees (used for wp and spline navigation)
171  float get_yaw() const;
172 
179  bool set_spline_destination(const Location_Class& destination, bool stopped_at_start, spline_segment_end_type seg_end_type, Location_Class next_destination);
180 
188  bool set_spline_destination(const Vector3f& destination, bool terrain_alt, bool stopped_at_start, spline_segment_end_type seg_end_type, const Vector3f& next_destination);
189 
195  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);
196 
199 
201  bool update_spline();
202 
206 
208  int32_t get_roll() const { return _pos_control.get_roll(); }
209  int32_t get_pitch() const { return _pos_control.get_pitch(); }
210 
212  bool advance_wp_target_along_track(float dt);
213 
214  static const struct AP_Param::GroupInfo var_info[];
215 
216 protected:
217 
218  // segment types, either straight or spine
219  enum SegmentType {
222  };
223 
224  // flags structure
225  struct wpnav_flags {
226  uint8_t reached_destination : 1; // true if we have reached the destination
227  uint8_t fast_waypoint : 1; // true if we should ignore the waypoint radius and consider the waypoint complete once the intermediate target has reached the waypoint
228  uint8_t slowing_down : 1; // true when target point is slowing down before reaching the destination
229  uint8_t recalc_wp_leash : 1; // true if we need to recalculate the leash lengths because of changes in speed or acceleration
230  uint8_t new_wp_destination : 1; // true if we have just received a new destination. allows us to freeze the position controller's xy feed forward
231  SegmentType segment_type : 1; // active segment is either straight or spline
232  uint8_t wp_yaw_set : 1; // true if yaw target has been set
233  } _flags;
234 
236  void calc_slow_down_distance(float speed_cms, float accel_cmss);
237 
239  float get_slow_down_speed(float dist_from_dest_cm, float accel_cmss);
240 
242 
244  void update_spline_solution(const Vector3f& origin, const Vector3f& dest, const Vector3f& origin_vel, const Vector3f& dest_vel);
245 
248  bool advance_spline_target_along_track(float dt);
249 
252  void calc_spline_pos_vel(float spline_time, Vector3f& position, Vector3f& velocity);
253 
254  // 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)
255  bool get_terrain_offset(float& offset_cm);
256 
257  // 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
258  // returns false if conversion failed (likely because terrain data was not available)
259  bool get_vector_NEU(const Location_Class &loc, Vector3f &vec, bool &terrain_alt);
260 
261  // set heading used for spline and waypoint navigation
262  void set_yaw_cd(float heading_cd);
263 
264  // references and pointers to external libraries
269  AP_Terrain *_terrain = nullptr;
270  AC_Avoid *_avoid = nullptr;
271 
272  // parameters
273  AP_Float _wp_speed_cms; // maximum horizontal speed in cm/s during missions
274  AP_Float _wp_speed_up_cms; // climb speed target in cm/s
275  AP_Float _wp_speed_down_cms; // descent speed target in cm/s
276  AP_Float _wp_radius_cm; // distance from a waypoint in cm that, when crossed, indicates the wp has been reached
277  AP_Float _wp_accel_cmss; // horizontal acceleration in cm/s/s during missions
278  AP_Float _wp_accel_z_cmss; // vertical acceleration in cm/s/s during missions
279 
280  // waypoint controller internal variables
281  uint32_t _wp_last_update; // time of last update_wpnav call
282  uint8_t _wp_step; // used to decide which portion of wpnav controller to run during this iteration
283  Vector3f _origin; // starting point of trip to next waypoint in cm from ekf origin
284  Vector3f _destination; // target destination in cm from ekf origin
285  Vector3f _pos_delta_unit; // each axis's percentage of the total track from origin to destination
286  float _track_length; // distance in cm between origin and destination
287  float _track_length_xy; // horizontal distance in cm between origin and destination
288  float _track_desired; // our desired distance along the track in cm
289  float _limited_speed_xy_cms; // horizontal speed in cm/s used to advance the intermediate target towards the destination. used to limit extreme acceleration after passing a waypoint
290  float _track_accel; // acceleration along track
291  float _track_speed; // speed in cm/s along track
292  float _track_leash_length; // leash length along track
293  float _slow_down_dist; // vehicle should begin to slow down once it is within this distance from the destination
294 
295  // spline variables
296  float _spline_time; // current spline time between origin and destination
297  float _spline_time_scale; // current spline time between origin and destination
298  Vector3f _spline_origin_vel; // the target velocity vector at the origin of the spline segment
299  Vector3f _spline_destination_vel;// the target velocity vector at the destination point of the spline segment
300  Vector3f _hermite_spline_solution[4]; // array describing spline path between origin and destination
302  float _yaw; // heading according to yaw
303 
304  // terrain following variables
305  bool _terrain_alt = false; // true if origin and destination.z are alt-above-terrain, false if alt-above-ekf-origin
309  bool _rangefinder_healthy = false;
310  float _rangefinder_alt_cm = 0.0f;
311 };
float _track_leash_length
Definition: AC_WPNav.h:292
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 check_wp_leash_length()
Definition: AC_WPNav.cpp:549
bool _ekf_origin_terrain_alt_set
Definition: AC_WPNav.h:306
bool reached_wp_destination() const
reached_destination - true when we have come within RADIUS cm of the waypoint
Definition: AC_WPNav.h:140
bool get_terrain_offset(float &offset_cm)
Definition: AC_WPNav.cpp:974
AP_Float _wp_radius_cm
Definition: AC_WPNav.h:276
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
Vector3f _origin
Definition: AC_WPNav.h:283
int32_t get_pitch() const
Definition: AC_WPNav.h:209
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
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
float get_pitch() const
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
bool _rangefinder_available
Definition: AC_WPNav.h:307
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
bool update_spline()
update_spline - update spline controller
Definition: AC_WPNav.cpp:803
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_accel_z() const
get_speed_z - returns target descent speed in cm/s during missions. Note: always positive ...
Definition: AC_WPNav.h:91
float _spline_time_scale
Definition: AC_WPNav.h:297
uint8_t _wp_step
Definition: AC_WPNav.h:282
const AP_InertialNav & _inav
Definition: AC_WPNav.h:265
int32_t get_roll() const
get desired roll, pitch which should be fed into stabilize controllers
Definition: AC_WPNav.h:208
float _track_accel
Definition: AC_WPNav.h:290
void init_brake_target(float accel_cmss)
init_brake_target - initializes stop position from current position and velocity
Definition: AC_WPNav.cpp:114
float get_speed_down() const
get_speed_down - returns target descent speed in cm/s during missions. Note: always positive ...
Definition: AC_WPNav.h:88
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
float get_speed_xy() const
get_speed_xy - allows main code to retrieve target horizontal velocity for wp navigation ...
Definition: AC_WPNav.h:82
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
AC_Avoid * _avoid
Definition: AC_WPNav.h:270
void set_avoidance(AC_Avoid *avoid_ptr)
provide pointer to avoidance library
Definition: AC_WPNav.h:55
float get_roll() const
get desired roll, pitch which should be fed into stabilize controllers
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
A system for managing and storing variables that are of general interest to the system.
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 _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
ArduCopter attitude control library.
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_WPNav.h:214
const Vector3f & get_wp_origin() const
get origin using position vector (distance from ekf origin in cm)
Definition: AC_WPNav.h:100
void set_fast_waypoint(bool fast)
set_fast_waypoint - set to true to ignore the waypoint radius and consider the waypoint &#39;reached&#39; the...
Definition: AC_WPNav.h:143
float get_wp_distance_to_destination() const
get_wp_distance_to_destination - get horizontal distance to destination in cm
Definition: AC_WPNav.cpp:498
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
float get_speed_up() const
get_speed_up - returns target climb speed in cm/s during missions
Definition: AC_WPNav.h:85
uint8_t reached_destination
Definition: AC_WPNav.h:226
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
void wp_and_spline_init()
Definition: AC_WPNav.cpp:149
bool _rangefinder_healthy
Definition: AC_WPNav.h:309
float _spline_time
Definition: AC_WPNav.h:296
bool reached_spline_destination() const
reached_spline_destination - true when we have come within RADIUS cm of the waypoint ...
Definition: AC_WPNav.h:198
AP_Int8 _rangefinder_use
Definition: AC_WPNav.h:308
float get_wp_acceleration() const
get_wp_acceleration - returns acceleration in cm/s/s during missions
Definition: AC_WPNav.h:94
Vector3f _hermite_spline_solution[4]
Definition: AC_WPNav.h:300
Common definitions and utility routines for the ArduPilot libraries.
AP_Terrain * _terrain
Definition: AC_WPNav.h:269
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_Float _wp_speed_down_cms
Definition: AC_WPNav.h:275
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
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 _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
struct AC_WPNav::wpnav_flags _flags
uint8_t new_wp_destination
Definition: AC_WPNav.h:230
void set_terrain(AP_Terrain *terrain_ptr)
provide pointer to terrain database
Definition: AC_WPNav.h:52
const AP_AHRS_View & _ahrs
Definition: AC_WPNav.h:266
void set_rangefinder_alt(bool use, bool healthy, float alt_cm)
provide rangefinder altitude
Definition: AC_WPNav.h:58
float _rangefinder_alt_cm
Definition: AC_WPNav.h:310
float _slow_down_dist
Definition: AC_WPNav.h:293
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