36 _pos_control(pos_control),
41 _angular_vel_max(0.0
f),
185 float dist =
norm(vec.
x, vec.
y);
float norm(const T first, const U second, const Params... parameters)
float get_speed_xy() const
void calc_velocities(bool init_velocity)
float get_alt_target() const
void set_desired_velocity_xy(float vel_lat_cms, float vel_lon_cms)
AC_PosControl & _pos_control
virtual const Vector3f & get_position() const =0
float safe_sqrt(const T v)
void set_desired_accel_xy(float accel_lat_cms, float accel_lon_cms)
#define AP_GROUPINFO(name, idx, clazz, element, def)
void update_xy_controller(float ekfNavVelGainScaler)
update_xy_controller - run the horizontal position controller - should be called at 100hz or higher ...
void update()
update - update circle controller
void init_start_angle(bool use_heading)
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
void set_xy_target(float x, float y)
set_xy_target in cm from home
float get_accel_xy() const
float wrap_PI(const T radian)
const Vector3f & get_pos_target() const
get_pos_target - get target as position vector (from home in cm)
#define AC_CIRCLE_ANGULAR_ACCEL_MIN
#define AC_CIRCLE_RADIUS_DEFAULT
bool is_zero(const T fVal1)
void init_xy_controller(bool reset_I=true)
const AP_AHRS_View & _ahrs
void set_rate(float deg_per_sec)
set_circle_rate - set circle rate in degrees per second
static const struct AP_Param::GroupInfo var_info[]
const AP_InertialNav & _inav
float constrain_float(const float amt, const float low, const float high)
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
void set_target_to_stopping_point_xy()
set_target_to_stopping_point_xy - sets horizontal target to reasonable stopping position in cm from h...
#define AC_CIRCLE_RATE_DEFAULT
AC_Circle(const AP_InertialNav &inav, const AP_AHRS_View &ahrs, AC_PosControl &pos_control)
Constructor.
void get_closest_point_on_circle(Vector3f &result)
void set_target_to_stopping_point_z()
set_target_to_stopping_point_z - sets altitude target to reasonable stopping altitude in cm above hom...
float time_since_last_xy_update() const
struct AC_Circle::circle_flags _flags
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)