2019-04-29 03:31:33 -03:00
# pragma once
# include <AP_Common/AP_Common.h>
2021-04-19 08:53:57 -03:00
# include <AP_Math/SCurve.h>
2019-04-29 03:31:33 -03:00
# include <APM_Control/AR_AttitudeControl.h>
2021-04-19 08:53:57 -03:00
# include <APM_Control/AR_PosControl.h>
2019-05-10 03:32:38 -03:00
# include <AC_Avoidance/AP_OAPathPlanner.h>
2021-11-18 02:55:56 -04:00
# include "AR_PivotTurn.h"
2019-04-29 03:31:33 -03:00
2019-05-09 07:48:48 -03:00
const float AR_WPNAV_HEADING_UNKNOWN = 99999.0f ; // used to indicate to set_desired_location method that next leg's heading is unknown
2019-04-29 03:31:33 -03:00
class AR_WPNav {
public :
// constructor
2021-04-19 08:53:57 -03:00
AR_WPNav ( AR_AttitudeControl & atc , AR_PosControl & pos_control ) ;
// initialise waypoint controller
// speed_max should be the max speed (in m/s) the vehicle will travel to waypoint. Leave as zero to use the default speed
// accel_max should be the max forward-back acceleration (in m/s/s). Leave as zero to use the attitude controller's default acceleration
// lat_accel_max should be the max right-left acceleration (in m/s/s). Leave as zero to use the attitude controller's default acceleration
// jerk_max should be the max forward-back and lateral jerk (in m/s/s/s). Leave as zero to use the attitude controller's default acceleration
void init ( float speed_max , float accel_max , float lat_accel_max , float jerk_max ) ;
2019-04-29 03:31:33 -03:00
// update navigation
void update ( float dt ) ;
// return desired speed
float get_desired_speed ( ) const { return _desired_speed ; }
// set desired speed in m/s
void set_desired_speed ( float speed ) { _desired_speed = MAX ( speed , 0.0f ) ; }
// restore desired speed to default from parameter value
void set_desired_speed_to_default ( ) { _desired_speed = _speed_max ; }
// execute the mission in reverse (i.e. drive backwards to destination)
bool get_reversed ( ) const { return _reversed ; }
void set_reversed ( bool reversed ) { _reversed = reversed ; }
// get navigation outputs for speed (in m/s) and turn rate (in rad/sec)
float get_speed ( ) const { return _desired_speed_limited ; }
float get_turn_rate_rads ( ) const { return _desired_turn_rate_rads ; }
// get desired lateral acceleration (for reporting purposes only because will be zero during pivot turns)
float get_lat_accel ( ) const { return _desired_lat_accel ; }
2021-04-19 08:53:57 -03:00
// set desired location and (optionally) next_destination
// next_destination should be provided if known to allow smooth cornering
bool set_desired_location ( const Location & destination , Location next_destination = Location ( ) ) WARN_IF_UNUSED ;
2019-04-29 03:31:33 -03:00
// set desired location to a reasonable stopping point, return true on success
2019-05-08 21:52:18 -03:00
bool set_desired_location_to_stopping_location ( ) WARN_IF_UNUSED ;
2019-04-29 03:31:33 -03:00
// set desired location as offset from the EKF origin, return true on success
2021-04-19 08:53:57 -03:00
bool set_desired_location_NED ( const Vector3f & destination ) WARN_IF_UNUSED ;
bool set_desired_location_NED ( const Vector3f & destination , const Vector3f & next_destination ) WARN_IF_UNUSED ;
2019-04-29 03:31:33 -03:00
// true if vehicle has reached desired location. defaults to true because this is normally used by missions and we do not want the mission to become stuck
bool reached_destination ( ) const { return _reached_destination ; }
// return distance (in meters) to destination
float get_distance_to_destination ( ) const { return _distance_to_destination ; }
2019-05-27 04:21:26 -03:00
// return true if destination is valid
bool is_destination_valid ( ) const { return _orig_and_dest_valid ; }
2019-04-29 03:31:33 -03:00
// get current destination. Note: this is not guaranteed to be valid (i.e. _orig_and_dest_valid is not checked)
const Location & get_destination ( ) { return _destination ; }
2019-05-10 03:32:38 -03:00
// get object avoidance adjusted destination. Note: this is not guaranteed to be valid (i.e. _orig_and_dest_valid is not checked)
const Location & get_oa_destination ( ) { return _oa_destination ; }
2021-11-20 00:02:04 -04:00
// return heading (in centi-degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)
2019-04-29 03:31:33 -03:00
float wp_bearing_cd ( ) const { return _wp_bearing_cd ; }
float nav_bearing_cd ( ) const { return _desired_heading_cd ; }
float crosstrack_error ( ) const { return _cross_track_error ; }
2019-08-23 07:49:06 -03:00
// return the heading (in centi-degrees) to the next waypoint accounting for OA, (used by sailboats)
float oa_wp_bearing_cd ( ) const { return _oa_wp_bearing_cd ; }
2019-04-29 03:31:33 -03:00
// settor to allow vehicle code to provide turn related param values to this library (should be updated regularly)
2021-05-02 13:37:03 -03:00
void set_turn_params ( float turn_radius , bool pivot_possible ) ;
2019-04-29 03:31:33 -03:00
// accessors for parameter values
float get_default_speed ( ) const { return _speed_max ; }
float get_radius ( ) const { return _radius ; }
2021-11-18 02:55:56 -04:00
float get_pivot_rate ( ) const { return _pivot . get_rate_max ( ) ; }
2019-04-29 03:31:33 -03:00
2019-09-26 20:18:46 -03:00
// calculate stopping location using current position and attitude controller provided maximum deceleration
// returns true on success, false on failure
bool get_stopping_location ( Location & stopping_loc ) WARN_IF_UNUSED ;
2019-04-29 03:31:33 -03:00
// parameter var table
static const struct AP_Param : : GroupInfo var_info [ ] ;
private :
// true if update has been called recently
bool is_active ( ) const ;
2021-04-19 08:53:57 -03:00
// move target location along track from origin to destination
void advance_wp_target_along_track ( const Location & current_loc , float dt ) ;
2019-04-29 03:31:33 -03:00
// update distance and bearing from vehicle's current position to destination
void update_distance_and_bearing_to_destination ( ) ;
2021-04-19 08:53:57 -03:00
// calculate steering and speed to drive along line from origin to destination waypoint
void update_steering_and_speed ( const Location & current_loc , float dt ) ;
2019-04-29 03:31:33 -03:00
2019-08-04 22:53:32 -03:00
// adjust speed to ensure it does not fall below value held in SPEED_MIN
2020-12-07 00:47:59 -04:00
// desired_speed should always be positive (or zero)
void apply_speed_min ( float & desired_speed ) const ;
2019-08-04 22:53:32 -03:00
2020-07-31 22:50:24 -03:00
// calculate the crosstrack error (does not rely on L1 controller)
float calc_crosstrack_error ( const Location & current_loc ) const ;
2019-04-29 03:31:33 -03:00
// parameters
AP_Float _speed_max ; // target speed between waypoints in m/s
2019-08-04 22:53:32 -03:00
AP_Float _speed_min ; // target speed minimum in m/s. Vehicle will not slow below this speed for corners
2019-04-29 03:31:33 -03:00
AP_Float _radius ; // distance in meters from a waypoint when we consider the waypoint has been reached
2021-11-18 02:55:56 -04:00
AR_PivotTurn _pivot ; // pivot turn controller
2019-04-29 03:31:33 -03:00
// references
AR_AttitudeControl & _atc ; // rover attitude control library
2021-04-19 08:53:57 -03:00
AR_PosControl & _pos_control ; // rover position control library
// scurve
SCurve _scurve_prev_leg ; // previous scurve trajectory used to blend with current scurve trajectory
SCurve _scurve_this_leg ; // current scurve trajectory
SCurve _scurve_next_leg ; // next scurve trajectory used to blend with current scurve trajectory
float _scurve_jerk ; // scurve jerk max in m/s/s/s
bool _fast_waypoint ; // true if vehicle will stop at the next waypoint
float _track_scalar_dt ; // time scaler to ensure scurve target doesn't get too far ahead of vehicle
2019-04-29 03:31:33 -03:00
// variables held in vehicle code (for now)
float _turn_radius ; // vehicle turn radius in meters
// variables for navigation
uint32_t _last_update_ms ; // system time of last call to update
Location _origin ; // origin Location (vehicle will travel from the origin to the destination)
Location _destination ; // destination Location when in Guided_WP
bool _orig_and_dest_valid ; // true if the origin and destination have been set
bool _reversed ; // execute the mission by backing up
// main outputs from navigation library
float _desired_speed ; // desired speed in m/s
2021-04-19 08:53:57 -03:00
float _desired_speed_limited ; // desired speed (above) but accel/decel limited
2019-04-29 03:31:33 -03:00
float _desired_turn_rate_rads ; // desired turn-rate in rad/sec (negative is counter clockwise, positive is clockwise)
float _desired_lat_accel ; // desired lateral acceleration (for reporting only)
float _desired_heading_cd ; // desired heading (back towards line between origin and destination)
float _wp_bearing_cd ; // heading to waypoint in centi-degrees
float _cross_track_error ; // cross track error (in meters). distance from current position to closest point on line between origin and destination
// variables for reporting
float _distance_to_destination ; // distance from vehicle to final destination in meters
bool _reached_destination ; // true once the vehicle has reached the destination
2019-05-10 03:32:38 -03:00
// object avoidance variables
bool _oa_active ; // true if we should use alternative destination to avoid obstacles
Location _oa_origin ; // intermediate origin during avoidance
Location _oa_destination ; // intermediate destination during avoidance
float _oa_distance_to_destination ; // OA (object avoidance) distance from vehicle to _oa_destination in meters
float _oa_wp_bearing_cd ; // OA adjusted heading to _oa_destination in centi-degrees
2019-04-29 03:31:33 -03:00
} ;