123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Param/AP_Param.h>
- #include <AP_Math/AP_Math.h>
- #include <GCS_MAVLink/GCS.h>
- #include <AC_PID/AC_P.h>
- #include <AP_RTC/JitterCorrection.h>
- class AP_Follow
- {
- public:
-
- enum YawBehave {
- YAW_BEHAVE_NONE = 0,
- YAW_BEHAVE_FACE_LEAD_VEHICLE = 1,
- YAW_BEHAVE_SAME_AS_LEAD_VEHICLE = 2,
- YAW_BEHAVE_DIR_OF_FLIGHT = 3
- };
-
- AP_Follow();
-
- bool enabled() const { return _enabled; }
-
- void set_target_sysid(uint8_t sysid) { _sysid = sysid; }
-
-
-
-
- bool have_target() const;
-
- bool get_target_location_and_velocity(Location &loc, Vector3f &vel_ned) const;
-
- bool get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_with_ofs, Vector3f &vel_ned);
-
- const AC_P& get_pos_p() const { return _p_pos; }
-
-
-
-
- YawBehave get_yaw_behave() const { return (YawBehave)_yaw_behave.get(); }
-
- bool get_target_heading_deg(float &heading) const;
-
- void handle_msg(const mavlink_message_t &msg);
-
-
-
-
- float get_distance_to_target() const { return _dist_to_target; }
-
- float get_bearing_to_target() const { return _bearing_to_target; }
-
- static const struct AP_Param::GroupInfo var_info[];
- private:
-
- bool get_velocity_ned(Vector3f &vel_ned, float dt) const;
-
- void init_offsets_if_required(const Vector3f &dist_vec_ned);
-
- bool get_offsets_ned(Vector3f &offsets) const;
-
- Vector3f rotate_vector(const Vector3f &vec, float angle_deg) const;
-
- void clear_dist_and_bearing_to_target();
-
- AP_Int8 _enabled;
- AP_Int16 _sysid;
- AP_Float _dist_max;
- AP_Int8 _offset_type;
- AP_Vector3f _offset;
- AP_Int8 _yaw_behave;
- AP_Int8 _alt_type;
- AC_P _p_pos;
-
- bool _healthy;
- uint32_t _last_location_update_ms;
- Location _target_location;
- Vector3f _target_velocity_ned;
- Vector3f _target_accel_ned;
- uint32_t _last_heading_update_ms;
- float _target_heading;
- bool _automatic_sysid;
- float _dist_to_target;
- float _bearing_to_target;
-
- JitterCorrection _jitter{3000};
- };
|