10 #define AC_CIRCLE_RADIUS_DEFAULT 1000.0f // radius of the circle in cm that the vehicle will fly 11 #define AC_CIRCLE_RATE_DEFAULT 20.0f // turn rate in deg/sec. Positive to turn clockwise, negative for counter clockwise 12 #define AC_CIRCLE_ANGULAR_ACCEL_MIN 2.0f // angular acceleration should never be less than 2deg/sec
void calc_velocities(bool init_velocity)
float get_radius()
get_radius - returns radius of circle in cm
AC_PosControl & _pos_control
void set_radius(float radius_cm)
set_radius - sets circle radius in cm
float get_distance_to_target() const
get_distance_to_target - get horizontal distance to position target in cm (used for reporting) ...
void update()
update - update circle controller
int32_t get_roll() const
get desired roll, pitch which should be fed into stabilize controllers
int32_t get_bearing_to_target() const
get bearing to target in centi-degrees
void init_start_angle(bool use_heading)
float get_roll() const
get desired roll, pitch which should be fed into stabilize controllers
A system for managing and storing variables that are of general interest to the system.
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
Common definitions and utility routines for the ArduPilot libraries.
int32_t get_pitch() const
int32_t get_bearing_to_target() const
get_bearing_to_target - get bearing to target position in centi-degrees
const Vector3f & get_center() const
get_circle_center in cm from home
float get_distance_to_target() const
get horizontal distance to loiter target in cm
void set_center(const Vector3f ¢er)
set_circle_center in cm from home
AC_Circle(const AP_InertialNav &inav, const AP_AHRS_View &ahrs, AC_PosControl &pos_control)
Constructor.
void get_closest_point_on_circle(Vector3f &result)
struct AC_Circle::circle_flags _flags
float get_angle_total() const
get_angle_total - return total angle in radians that vehicle has circled