AC_Circle.h 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104
  1. #pragma once
  2. #include <AP_Common/AP_Common.h>
  3. #include <AP_Param/AP_Param.h>
  4. #include <AP_Math/AP_Math.h>
  5. #include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library
  6. #include <AC_AttitudeControl/AC_PosControl.h> // Position control library
  7. // loiter maximum velocities and accelerations
  8. #define AC_CIRCLE_RADIUS_DEFAULT 1000.0f // radius of the circle in cm that the vehicle will fly
  9. #define AC_CIRCLE_RATE_DEFAULT 20.0f // turn rate in deg/sec. Positive to turn clockwise, negative for counter clockwise
  10. #define AC_CIRCLE_ANGULAR_ACCEL_MIN 2.0f // angular acceleration should never be less than 2deg/sec
  11. class AC_Circle
  12. {
  13. public:
  14. /// Constructor
  15. AC_Circle(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control);
  16. /// init - initialise circle controller setting center specifically
  17. /// caller should set the position controller's x,y and z speeds and accelerations before calling this
  18. void init(const Vector3f& center);
  19. /// init - initialise circle controller setting center using stopping point and projecting out based on the copter's heading
  20. /// caller should set the position controller's x,y and z speeds and accelerations before calling this
  21. void init();
  22. /// set_circle_center in cm from home
  23. void set_center(const Vector3f& center) { _center = center; }
  24. /// get_circle_center in cm from home
  25. const Vector3f& get_center() const { return _center; }
  26. /// get_radius - returns radius of circle in cm
  27. float get_radius() { return _radius; }
  28. /// set_radius - sets circle radius in cm
  29. void set_radius(float radius_cm) { _radius = radius_cm; }
  30. /// set_circle_rate - set circle rate in degrees per second
  31. void set_rate(float deg_per_sec);
  32. /// get_angle_total - return total angle in radians that vehicle has circled
  33. float get_angle_total() const { return _angle_total; }
  34. /// update - update circle controller
  35. void update();
  36. /// get desired roll, pitch which should be fed into stabilize controllers
  37. float get_roll() const { return _pos_control.get_roll(); }
  38. float get_pitch() const { return _pos_control.get_pitch(); }
  39. float get_yaw() const { return _yaw; }
  40. // get_closest_point_on_circle - returns closest point on the circle
  41. // circle's center should already have been set
  42. // closest point on the circle will be placed in result
  43. // result's altitude (i.e. z) will be set to the circle_center's altitude
  44. // if vehicle is at the center of the circle, the edge directly behind vehicle will be returned
  45. void get_closest_point_on_circle(Vector3f &result);
  46. /// get horizontal distance to loiter target in cm
  47. float get_distance_to_target() const { return _pos_control.get_distance_to_target(); }
  48. /// get bearing to target in centi-degrees
  49. int32_t get_bearing_to_target() const { return _pos_control.get_bearing_to_target(); }
  50. static const struct AP_Param::GroupInfo var_info[];
  51. private:
  52. // calc_velocities - calculate angular velocity max and acceleration based on radius and rate
  53. // this should be called whenever the radius or rate are changed
  54. // initialises the yaw and current position around the circle
  55. // init_velocity should be set true if vehicle is just starting circle
  56. void calc_velocities(bool init_velocity);
  57. // init_start_angle - sets the starting angle around the circle and initialises the angle_total
  58. // if use_heading is true the vehicle's heading will be used to init the angle causing minimum yaw movement
  59. // if use_heading is false the vehicle's position from the center will be used to initialise the angle
  60. void init_start_angle(bool use_heading);
  61. // flags structure
  62. struct circle_flags {
  63. uint8_t panorama : 1; // true if we are doing a panorama
  64. } _flags;
  65. // references to inertial nav and ahrs libraries
  66. const AP_InertialNav& _inav;
  67. const AP_AHRS_View& _ahrs;
  68. AC_PosControl& _pos_control;
  69. // parameters
  70. AP_Float _radius; // maximum horizontal speed in cm/s during missions
  71. AP_Float _rate; // rotation speed in deg/sec
  72. // internal variables
  73. Vector3f _center; // center of circle in cm from home
  74. float _yaw; // yaw heading (normally towards circle center)
  75. float _angle; // current angular position around circle in radians (0=directly north of the center of the circle)
  76. float _angle_total; // total angle traveled in radians
  77. float _angular_vel; // angular velocity in radians/sec
  78. float _angular_vel_max; // maximum velocity in radians/sec
  79. float _angular_accel; // angular acceleration in radians/sec/sec
  80. };