APM:Libraries
AP_Follow.h
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 #include <AP_Common/AP_Common.h>
18 #include <AP_HAL/AP_HAL.h>
19 #include <AP_Param/AP_Param.h>
20 #include <AP_Math/AP_Math.h>
21 #include <AP_AHRS/AP_AHRS.h>
22 #include <GCS_MAVLink/GCS.h>
23 #include <AC_PID/AC_P.h>
24 
25 class AP_Follow
26 {
27 
28 public:
29 
30  // enum for YAW_BEHAVE parameter
31  enum YawBehave {
36  };
37 
38  // constructor
39  AP_Follow();
40 
41  // set which target to follow
42  void set_target_sysid(uint8_t sysid) { _sysid = sysid; }
43 
44  //
45  // position tracking related methods
46  //
47 
48  // true if we have a valid target location estimate
49  bool have_target() const;
50 
51  // get target's estimated location and velocity (in NED)
52  bool get_target_location_and_velocity(Location &loc, Vector3f &vel_ned) const;
53 
54  // get distance vector to target (in meters), target plus offsets, and target's velocity all in NED frame
55  bool get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_with_ofs, Vector3f &vel_ned);
56 
57  // get position controller. this controller is not used within this library but it is convenient to hold it here
58  const AC_P& get_pos_p() const { return _p_pos; }
59 
60  //
61  // yaw/heading related methods
62  //
63 
64  // get user defined yaw behaviour
65  YawBehave get_yaw_behave() const { return (YawBehave)_yaw_behave.get(); }
66 
67  // get target's heading in degrees (0 = north, 90 = east)
68  bool get_target_heading(float &heading) const;
69 
70  // parse mavlink messages which may hold target's position, velocity and attitude
71  void handle_msg(const mavlink_message_t &msg);
72 
73  // parameter list
74  static const struct AP_Param::GroupInfo var_info[];
75 
76  // returns true if library is enabled
77  bool enabled() const { return _enabled; }
78 
79 private:
80 
81  // get velocity estimate in m/s in NED frame using dt since last update
82  bool get_velocity_ned(Vector3f &vel_ned, float dt) const;
83 
84  // initialise offsets to provided distance vector (in meters in NED frame) if required
85  void init_offsets_if_required(const Vector3f &dist_vec_ned);
86 
87  // get offsets in meters in NED frame
88  bool get_offsets_ned(Vector3f &offsets) const;
89 
90  // parameters
91  AP_Int8 _enabled; // 1 if this subsystem is enabled
92  AP_Int16 _sysid; // target's mavlink system id (0 to use first sysid seen)
93  AP_Float _dist_max; // maximum distance to target. targets further than this will be ignored
94  AP_Int8 _offset_type; // offset frame type (0:North-East-Down, 1:RelativeToLeadVehicleHeading)
95  AP_Vector3f _offset; // offset from lead vehicle in meters
96  AP_Int8 _yaw_behave; // following vehicle's yaw/heading behaviour
97  AC_P _p_pos; // position error P controller
98 
99  // local variables
100  bool _healthy; // true if we are receiving mavlink messages (regardless of whether they have target position info within them)
101  uint8_t _sysid_to_follow = 0; // mavlink system id of vehicle to follow
102  uint32_t _last_location_update_ms; // system time of last position update
103  Location _target_location; // last known location of target
104  Vector3f _target_velocity_ned; // last known velocity of target in NED frame in m/s
105  Vector3f _target_accel_ned; // last known acceleration of target in NED frame in m/s/s
106  uint32_t _last_heading_update_ms; // system time of last heading update
107  float _target_heading; // heading in degrees
108  uint32_t _last_location_sent_to_gcs; // last time GCS was told position
109 };
void set_target_sysid(uint8_t sysid)
Definition: AP_Follow.h:42
float _target_heading
Definition: AP_Follow.h:107
bool get_target_location_and_velocity(Location &loc, Vector3f &vel_ned) const
Definition: AP_Follow.cpp:125
AP_Float _dist_max
Definition: AP_Follow.h:93
bool get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_with_ofs, Vector3f &vel_ned)
Definition: AP_Follow.cpp:156
uint32_t _last_location_sent_to_gcs
Definition: AP_Follow.h:108
Interface definition for the various Ground Control System.
YawBehave get_yaw_behave() const
Definition: AP_Follow.h:65
bool get_velocity_ned(Vector3f &vel_ned, float dt) const
Definition: AP_Follow.cpp:300
bool get_offsets_ned(Vector3f &offsets) const
Definition: AP_Follow.cpp:315
AP_Int8 _offset_type
Definition: AP_Follow.h:94
Object managing one P controller.
Definition: AC_P.h:13
A system for managing and storing variables that are of general interest to the system.
bool enabled() const
Definition: AP_Follow.h:77
bool have_target() const
AC_P _p_pos
Definition: AP_Follow.h:97
Vector3f _target_accel_ned
Definition: AP_Follow.h:105
bool get_target_heading(float &heading) const
Definition: AP_Follow.cpp:196
void init_offsets_if_required(const Vector3f &dist_vec_ned)
Definition: AP_Follow.cpp:307
AP_Int8 _yaw_behave
Definition: AP_Follow.h:96
const AC_P & get_pos_p() const
Definition: AP_Follow.h:58
bool _healthy
Definition: AP_Follow.h:100
Common definitions and utility routines for the ArduPilot libraries.
AP_Int8 _enabled
Definition: AP_Follow.h:91
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Follow.h:74
Vector3f _target_velocity_ned
Definition: AP_Follow.h:104
uint8_t _sysid_to_follow
Definition: AP_Follow.h:101
AP_Int16 _sysid
Definition: AP_Follow.h:92
uint32_t _last_heading_update_ms
Definition: AP_Follow.h:106
uint32_t _last_location_update_ms
Definition: AP_Follow.h:102
Location _target_location
Definition: AP_Follow.h:103
AP_Vector3f _offset
Definition: AP_Follow.h:95
void handle_msg(const mavlink_message_t &msg)
Definition: AP_Follow.cpp:214