123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_Param/AP_Param.h>
- #include <AP_Math/AP_Math.h>
- #include <AC_AttitudeControl/AC_AttitudeControl.h> // Attitude controller library for sqrt controller
- #define AC_AVOID_ACCEL_CMSS_MAX 100.0f
- #define AC_AVOID_DISABLED 0
- #define AC_AVOID_STOP_AT_FENCE 1
- #define AC_AVOID_USE_PROXIMITY_SENSOR 2
- #define AC_AVOID_STOP_AT_BEACON_FENCE 4
- #define AC_AVOID_DEFAULT (AC_AVOID_STOP_AT_FENCE | AC_AVOID_USE_PROXIMITY_SENSOR)
- #define AC_AVOID_NONGPS_DIST_MAX_DEFAULT 5.0f
- #define AC_AVOID_ANGLE_MAX_PERCENT 0.75f
- class AC_Avoid {
- public:
- AC_Avoid();
-
- AC_Avoid(const AC_Avoid &other) = delete;
- AC_Avoid &operator=(const AC_Avoid&) = delete;
-
- static AC_Avoid *get_singleton() {
- return _singleton;
- }
-
- void adjust_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt);
- void adjust_velocity(float kP, float accel_cmss, Vector3f &desired_vel_cms, float dt);
-
-
-
-
-
-
- void adjust_speed(float kP, float accel, float heading, float &speed, float dt);
-
- void adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt);
-
-
-
- void adjust_roll_pitch(float &roll, float &pitch, float angle_max);
-
- void proximity_avoidance_enable(bool on_off) { _proximity_enabled = on_off; }
- bool proximity_avoidance_enabled() { return _proximity_enabled; }
-
-
-
-
-
- void limit_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f& limit_direction, float limit_distance_cm, float dt) const;
-
-
-
- float get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const;
- static const struct AP_Param::GroupInfo var_info[];
- private:
-
- enum BehaviourType {
- BEHAVIOR_SLIDE = 0,
- BEHAVIOR_STOP = 1
- };
-
- void adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt);
-
- void adjust_velocity_polygon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt);
-
- void adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt);
-
- void adjust_velocity_proximity(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt);
-
- void adjust_velocity_polygon(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f* boundary, uint16_t num_points, bool earth_frame, float margin, float dt);
-
- float get_stopping_distance(float kP, float accel_cmss, float speed_cms) const;
-
-
- float distance_to_lean_pct(float dist_m);
-
- void get_proximity_roll_pitch_pct(float &roll_positive, float &roll_negative, float &pitch_positive, float &pitch_negative);
-
- AP_Int8 _enabled;
- AP_Int16 _angle_max;
- AP_Float _dist_max;
- AP_Float _margin;
- AP_Int8 _behavior;
- bool _proximity_enabled = true;
- static AC_Avoid *_singleton;
- };
- namespace AP {
- AC_Avoid *ac_avoid();
- };
|