APM:Libraries
AC_Circle.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_Param/AP_Param.h>
5 #include <AP_Math/AP_Math.h>
6 #include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library
7 #include <AC_AttitudeControl/AC_PosControl.h> // Position control library
8 
9 // loiter maximum velocities and accelerations
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
13 
14 class AC_Circle
15 {
16 public:
17 
19  AC_Circle(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control);
20 
23  void init(const Vector3f& center);
24 
27  void init();
28 
30  void set_center(const Vector3f& center) { _center = center; }
31 
33  const Vector3f& get_center() const { return _center; }
34 
36  float get_radius() { return _radius; }
38  void set_radius(float radius_cm) { _radius = radius_cm; }
39 
41  void set_rate(float deg_per_sec);
42 
44  float get_angle_total() const { return _angle_total; }
45 
47  void update();
48 
50  int32_t get_roll() const { return _pos_control.get_roll(); }
51  int32_t get_pitch() const { return _pos_control.get_pitch(); }
52  int32_t get_yaw() const { return _yaw; }
53 
54  // get_closest_point_on_circle - returns closest point on the circle
55  // circle's center should already have been set
56  // closest point on the circle will be placed in result
57  // result's altitude (i.e. z) will be set to the circle_center's altitude
58  // if vehicle is at the center of the circle, the edge directly behind vehicle will be returned
60 
63 
66 
67  static const struct AP_Param::GroupInfo var_info[];
68 
69 private:
70 
71  // calc_velocities - calculate angular velocity max and acceleration based on radius and rate
72  // this should be called whenever the radius or rate are changed
73  // initialises the yaw and current position around the circle
74  // init_velocity should be set true if vehicle is just starting circle
75  void calc_velocities(bool init_velocity);
76 
77  // init_start_angle - sets the starting angle around the circle and initialises the angle_total
78  // if use_heading is true the vehicle's heading will be used to init the angle causing minimum yaw movement
79  // if use_heading is false the vehicle's position from the center will be used to initialise the angle
80  void init_start_angle(bool use_heading);
81 
82  // flags structure
83  struct circle_flags {
84  uint8_t panorama : 1; // true if we are doing a panorama
85  } _flags;
86 
87  // references to inertial nav and ahrs libraries
91 
92  // parameters
93  AP_Float _radius; // maximum horizontal speed in cm/s during missions
94  AP_Float _rate; // rotation speed in deg/sec
95 
96  // internal variables
97  Vector3f _center; // center of circle in cm from home
98  float _yaw; // yaw heading (normally towards circle center)
99  float _angle; // current angular position around circle in radians (0=directly north of the center of the circle)
100  float _angle_total; // total angle traveled in radians
101  float _angular_vel; // angular velocity in radians/sec
102  float _angular_vel_max; // maximum velocity in radians/sec
103  float _angular_accel; // angular acceleration in radians/sec/sec
104 };
void calc_velocities(bool init_velocity)
Definition: AC_Circle.cpp:204
float get_radius()
get_radius - returns radius of circle in cm
Definition: AC_Circle.h:36
AC_PosControl & _pos_control
Definition: AC_Circle.h:90
void set_radius(float radius_cm)
set_radius - sets circle radius in cm
Definition: AC_Circle.h:38
int32_t get_yaw() const
Definition: AC_Circle.h:52
float _yaw
Definition: AC_Circle.h:98
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
float get_distance_to_target() const
get_distance_to_target - get horizontal distance to position target in cm (used for reporting) ...
float get_pitch() const
void update()
update - update circle controller
Definition: AC_Circle.cpp:110
int32_t get_roll() const
get desired roll, pitch which should be fed into stabilize controllers
Definition: AC_Circle.h:50
const char * result
Definition: Printf.cpp:16
float _angular_vel
Definition: AC_Circle.h:101
int32_t get_bearing_to_target() const
get bearing to target in centi-degrees
Definition: AC_Circle.h:65
void init_start_angle(bool use_heading)
Definition: AC_Circle.cpp:231
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
Definition: AC_Circle.h:89
float _angular_vel_max
Definition: AC_Circle.h:102
void set_rate(float deg_per_sec)
set_circle_rate - set circle rate in degrees per second
Definition: AC_Circle.cpp:101
float _angular_accel
Definition: AC_Circle.h:103
void init()
Definition: AC_Circle.cpp:74
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_Circle.h:67
const AP_InertialNav & _inav
Definition: AC_Circle.h:88
Common definitions and utility routines for the ArduPilot libraries.
int32_t get_pitch() const
Definition: AC_Circle.h:51
int32_t get_bearing_to_target() const
get_bearing_to_target - get bearing to target position in centi-degrees
AP_Float _radius
Definition: AC_Circle.h:93
const Vector3f & get_center() const
get_circle_center in cm from home
Definition: AC_Circle.h:33
float get_distance_to_target() const
get horizontal distance to loiter target in cm
Definition: AC_Circle.h:62
void set_center(const Vector3f &center)
set_circle_center in cm from home
Definition: AC_Circle.h:30
AC_Circle(const AP_InertialNav &inav, const AP_AHRS_View &ahrs, AC_PosControl &pos_control)
Constructor.
Definition: AC_Circle.cpp:33
void get_closest_point_on_circle(Vector3f &result)
Definition: AC_Circle.cpp:170
float _angle
Definition: AC_Circle.h:99
AP_Float _rate
Definition: AC_Circle.h:94
Vector3f _center
Definition: AC_Circle.h:97
float _angle_total
Definition: AC_Circle.h:100
struct AC_Circle::circle_flags _flags
float get_angle_total() const
get_angle_total - return total angle in radians that vehicle has circled
Definition: AC_Circle.h:44