AP_Follow.h 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_HAL/AP_HAL.h>
  16. #include <AP_Param/AP_Param.h>
  17. #include <AP_Math/AP_Math.h>
  18. #include <GCS_MAVLink/GCS.h>
  19. #include <AC_PID/AC_P.h>
  20. #include <AP_RTC/JitterCorrection.h>
  21. class AP_Follow
  22. {
  23. public:
  24. // enum for YAW_BEHAVE parameter
  25. enum YawBehave {
  26. YAW_BEHAVE_NONE = 0,
  27. YAW_BEHAVE_FACE_LEAD_VEHICLE = 1,
  28. YAW_BEHAVE_SAME_AS_LEAD_VEHICLE = 2,
  29. YAW_BEHAVE_DIR_OF_FLIGHT = 3
  30. };
  31. // constructor
  32. AP_Follow();
  33. // returns true if library is enabled
  34. bool enabled() const { return _enabled; }
  35. // set which target to follow
  36. void set_target_sysid(uint8_t sysid) { _sysid = sysid; }
  37. //
  38. // position tracking related methods
  39. //
  40. // true if we have a valid target location estimate
  41. bool have_target() const;
  42. // get target's estimated location and velocity (in NED)
  43. bool get_target_location_and_velocity(Location &loc, Vector3f &vel_ned) const;
  44. // get distance vector to target (in meters), target plus offsets, and target's velocity all in NED frame
  45. bool get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_with_ofs, Vector3f &vel_ned);
  46. // get position controller. this controller is not used within this library but it is convenient to hold it here
  47. const AC_P& get_pos_p() const { return _p_pos; }
  48. //
  49. // yaw/heading related methods
  50. //
  51. // get user defined yaw behaviour
  52. YawBehave get_yaw_behave() const { return (YawBehave)_yaw_behave.get(); }
  53. // get target's heading in degrees (0 = north, 90 = east)
  54. bool get_target_heading_deg(float &heading) const;
  55. // parse mavlink messages which may hold target's position, velocity and attitude
  56. void handle_msg(const mavlink_message_t &msg);
  57. //
  58. // GCS reporting functions
  59. //
  60. // get horizontal distance to target (including offset) in meters (for reporting purposes)
  61. float get_distance_to_target() const { return _dist_to_target; }
  62. // get bearing to target (including offset) in degrees (for reporting purposes)
  63. float get_bearing_to_target() const { return _bearing_to_target; }
  64. // parameter list
  65. static const struct AP_Param::GroupInfo var_info[];
  66. private:
  67. // get velocity estimate in m/s in NED frame using dt since last update
  68. bool get_velocity_ned(Vector3f &vel_ned, float dt) const;
  69. // initialise offsets to provided distance vector to other vehicle (in meters in NED frame) if required
  70. void init_offsets_if_required(const Vector3f &dist_vec_ned);
  71. // get offsets in meters in NED frame
  72. bool get_offsets_ned(Vector3f &offsets) const;
  73. // rotate 3D vector clockwise by specified angle (in degrees)
  74. Vector3f rotate_vector(const Vector3f &vec, float angle_deg) const;
  75. // set recorded distance and bearing to target to zero
  76. void clear_dist_and_bearing_to_target();
  77. // parameters
  78. AP_Int8 _enabled; // 1 if this subsystem is enabled
  79. AP_Int16 _sysid; // target's mavlink system id (0 to use first sysid seen)
  80. AP_Float _dist_max; // maximum distance to target. targets further than this will be ignored
  81. AP_Int8 _offset_type; // offset frame type (0:North-East-Down, 1:RelativeToLeadVehicleHeading)
  82. AP_Vector3f _offset; // offset from lead vehicle in meters
  83. AP_Int8 _yaw_behave; // following vehicle's yaw/heading behaviour (see YAW_BEHAVE enum)
  84. AP_Int8 _alt_type; // altitude source for follow mode
  85. AC_P _p_pos; // position error P controller
  86. // local variables
  87. bool _healthy; // true if we are receiving mavlink messages (regardless of whether they have target position info within them)
  88. uint32_t _last_location_update_ms; // system time of last position update
  89. Location _target_location; // last known location of target
  90. Vector3f _target_velocity_ned; // last known velocity of target in NED frame in m/s
  91. Vector3f _target_accel_ned; // last known acceleration of target in NED frame in m/s/s
  92. uint32_t _last_heading_update_ms; // system time of last heading update
  93. float _target_heading; // heading in degrees
  94. bool _automatic_sysid; // did we lock onto a sysid automatically?
  95. float _dist_to_target; // latest distance to target in meters (for reporting purposes)
  96. float _bearing_to_target; // latest bearing to target in degrees (for reporting purposes)
  97. // setup jitter correction with max transport lag of 3s
  98. JitterCorrection _jitter{3000};
  99. };