123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_Param/AP_Param.h>
- #include <AP_Math/AP_Math.h>
- #include <AP_Common/Location.h>
- #include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library
- #include <AC_AttitudeControl/AC_PosControl.h> // Position control library
- #include <AC_AttitudeControl/AC_AttitudeControl.h> // Attitude control library
- #include <AP_Terrain/AP_Terrain.h>
- #include <AC_Avoidance/AC_Avoid.h> // Stop at fence library
- #define WPNAV_ACCELERATION 100.0f
- #define WPNAV_ACCELERATION_MIN 50.0f
- #define WPNAV_WP_SPEED 500.0f
- #define WPNAV_WP_SPEED_MIN 20.0f
- #define WPNAV_WP_TRACK_SPEED_MIN 50.0f
- #define WPNAV_WP_RADIUS 200.0f
- #define WPNAV_WP_RADIUS_MIN 5.0f
- #define WPNAV_WP_SPEED_UP 250.0f
- #define WPNAV_WP_SPEED_DOWN 150.0f
- #define WPNAV_WP_ACCEL_Z_DEFAULT 100.0f
- #define WPNAV_LEASH_LENGTH_MIN 100.0f
- #define WPNAV_WP_FAST_OVERSHOOT_MAX 200.0f
- #define WPNAV_YAW_DIST_MIN 200
- #define WPNAV_YAW_LEASH_PCT_MIN 0.134f
- #define WPNAV_RANGEFINDER_FILT_Z 0.25f
- class AC_WPNav
- {
- public:
-
- enum spline_segment_end_type {
- SEGMENT_END_STOP = 0,
- SEGMENT_END_STRAIGHT,
- SEGMENT_END_SPLINE
- };
-
- AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control);
-
- void set_terrain(AP_Terrain* terrain_ptr) { _terrain = terrain_ptr; }
-
- void set_rangefinder_alt(bool use, bool healthy, float alt_cm) { _rangefinder_available = use; _rangefinder_healthy = healthy; _rangefinder_alt_cm = alt_cm; }
-
- bool rangefinder_used() const { return _rangefinder_use && _rangefinder_healthy; }
-
-
-
-
-
-
- void wp_and_spline_init();
-
- void set_speed_xy(float speed_cms);
-
- void set_speed_up(float speed_up_cms);
- void set_speed_down(float speed_down_cms);
-
- float get_default_speed_xy() const { return _wp_speed_cms; }
-
- float get_default_speed_up() const { return _wp_speed_up_cms; }
-
- float get_default_speed_down() const { return _wp_speed_down_cms; }
-
- float get_accel_z() const { return _wp_accel_z_cmss; }
-
- float get_wp_acceleration() const { return _wp_accel_cmss.get(); }
-
- const Vector3f &get_wp_destination() const { return _destination; }
-
- const Vector3f &get_wp_origin() const { return _origin; }
-
- bool origin_and_destination_are_terrain_alt() const { return _terrain_alt; }
-
-
- bool set_wp_destination(const Location& destination);
-
-
-
- bool get_wp_destination(Location& destination) const;
-
-
- virtual bool get_oa_wp_destination(Location& destination) const { return get_wp_destination(destination); }
-
-
- bool set_wp_destination(const Vector3f& destination, bool terrain_alt = false);
-
- bool set_wp_destination_NED(const Vector3f& destination_NED);
-
-
-
- virtual bool set_wp_origin_and_destination(const Vector3f& origin, const Vector3f& destination, bool terrain_alt = false);
-
-
-
- void shift_wp_origin_to_current_pos();
-
-
- void get_wp_stopping_point_xy(Vector3f& stopping_point) const;
- void get_wp_stopping_point(Vector3f& stopping_point) const;
-
- virtual float get_wp_distance_to_destination() const;
-
- virtual int32_t get_wp_bearing_to_destination() const;
-
- virtual bool reached_wp_destination() const { return _flags.reached_destination; }
-
- bool reached_wp_destination_xy() const {
- return get_wp_distance_to_destination() < _wp_radius_cm;
- }
-
- void set_fast_waypoint(bool fast) { _flags.fast_waypoint = fast; }
-
- virtual bool update_wpnav();
-
-
- void check_wp_leash_length();
-
- void calculate_wp_leash_length();
-
-
-
-
-
-
-
-
-
-
-
-
-
- float get_yaw() const;
-
-
-
-
-
-
- bool set_spline_destination(const Location& destination, bool stopped_at_start, spline_segment_end_type seg_end_type, Location next_destination);
-
-
-
-
-
-
-
- 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);
-
-
-
-
-
- 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);
-
- bool reached_spline_destination() const { return _flags.reached_destination; }
-
- bool update_spline();
-
-
-
-
- float get_roll() const { return _pos_control.get_roll(); }
- float get_pitch() const { return _pos_control.get_pitch(); }
-
- bool advance_wp_target_along_track(float dt);
-
- float crosstrack_error() const { return _track_error_xy;}
- static const struct AP_Param::GroupInfo var_info[];
- protected:
-
- enum SegmentType {
- SEGMENT_STRAIGHT = 0,
- SEGMENT_SPLINE = 1
- };
-
- struct wpnav_flags {
- uint8_t reached_destination : 1;
- uint8_t fast_waypoint : 1;
- uint8_t slowing_down : 1;
- uint8_t recalc_wp_leash : 1;
- uint8_t new_wp_destination : 1;
- SegmentType segment_type : 1;
- uint8_t wp_yaw_set : 1;
- } _flags;
-
- void calc_slow_down_distance(float speed_cms, float accel_cmss);
-
- float get_slow_down_speed(float dist_from_dest_cm, float accel_cmss);
-
-
- void update_spline_solution(const Vector3f& origin, const Vector3f& dest, const Vector3f& origin_vel, const Vector3f& dest_vel);
-
-
- bool advance_spline_target_along_track(float dt);
-
-
- void calc_spline_pos_vel(float spline_time, Vector3f& position, Vector3f& velocity);
-
- bool get_terrain_offset(float& offset_cm);
-
-
- bool get_vector_NEU(const Location &loc, Vector3f &vec, bool &terrain_alt);
-
- void set_yaw_cd(float heading_cd);
-
- const AP_InertialNav& _inav;
- const AP_AHRS_View& _ahrs;
- AC_PosControl& _pos_control;
- const AC_AttitudeControl& _attitude_control;
- AP_Terrain *_terrain;
-
- AP_Float _wp_speed_cms;
- AP_Float _wp_speed_up_cms;
- AP_Float _wp_speed_down_cms;
- AP_Float _wp_radius_cm;
- AP_Float _wp_accel_cmss;
- AP_Float _wp_accel_z_cmss;
-
- uint32_t _wp_last_update;
- Vector3f _origin;
- Vector3f _destination;
- Vector3f _pos_delta_unit;
- float _track_error_xy;
- float _track_length;
- float _track_length_xy;
- float _track_desired;
- float _limited_speed_xy_cms;
- float _track_accel;
- float _track_speed;
- float _track_leash_length;
- float _slow_down_dist;
-
- float _spline_time;
- float _spline_time_scale;
- Vector3f _spline_origin_vel;
- Vector3f _spline_destination_vel;
- Vector3f _hermite_spline_solution[4];
- float _spline_vel_scaler;
- float _yaw;
-
- bool _terrain_alt;
- bool _rangefinder_available;
- AP_Int8 _rangefinder_use;
- bool _rangefinder_healthy;
- float _rangefinder_alt_cm;
- };
|