12 #define AC_AVOID_ACCEL_CMSS_MAX 100.0f // maximum acceleration/deceleration in cm/s/s used to avoid hitting fence 15 #define AC_AVOID_DISABLED 0 // avoidance disabled 16 #define AC_AVOID_STOP_AT_FENCE 1 // stop at fence 17 #define AC_AVOID_USE_PROXIMITY_SENSOR 2 // stop based on proximity sensor output 18 #define AC_AVOID_STOP_AT_BEACON_FENCE 4 // stop based on beacon perimeter 19 #define AC_AVOID_DEFAULT (AC_AVOID_STOP_AT_FENCE | AC_AVOID_USE_PROXIMITY_SENSOR) 22 #define AC_AVOID_NONGPS_DIST_MAX_DEFAULT 5.0f // objects over 5m away are ignored (default value for DIST_MAX parameter) 23 #define AC_AVOID_ANGLE_MAX_PERCENT 0.75f // object avoidance max lean angle as a percentage (expressed in 0 ~ 1 range) of total vehicle max lean angle 51 void adjust_speed(
float kP,
float accel,
float heading,
float &speed,
float dt);
54 void adjust_velocity_z(
float kP,
float accel_cmss,
float& climb_rate_cms,
float dt);
71 void limit_velocity(
float kP,
float accel_cmss,
Vector2f &desired_vel_cms,
const Vector2f& limit_direction,
float limit_distance_cm,
float dt)
const;
76 float get_max_speed(
float kP,
float accel_cmss,
float distance_cm,
float dt)
const;
void get_proximity_roll_pitch_pct(float &roll_positive, float &roll_negative, float &pitch_positive, float &pitch_negative)
AC_Avoid & operator=(const AC_Avoid &)=delete
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)
void proximity_avoidance_enable(bool on_off)
float get_stopping_distance(float kP, float accel_cmss, float speed_cms) const
static const struct AP_Param::GroupInfo var_info[]
void adjust_roll_pitch(float &roll, float &pitch, float angle_max)
A system for managing and storing variables that are of general interest to the system.
ArduCopter attitude control library.
void adjust_velocity_polygon_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)
float get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const
Common definitions and utility routines for the ArduPilot libraries.
void adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
AC_Avoid(const AP_AHRS &ahrs, const AC_Fence &fence, const AP_Proximity &proximity, const AP_Beacon *beacon=nullptr)
Constructor.
void limit_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f &limit_direction, float limit_distance_cm, float dt) const
void adjust_velocity_z(float kP, float accel_cmss, float &climb_rate_cms, float dt)
void adjust_speed(float kP, float accel, float heading, float &speed, float dt)
bool proximity_avoidance_enabled()
const AP_Proximity & _proximity
void adjust_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
const AP_Beacon * _beacon
void adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
float distance_to_lean_pct(float dist_m)