APM:Libraries
AP_Follow.cpp
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 
16 #include <AP_HAL/AP_HAL.h>
17 #include <GCS_MAVLink/GCS.h>
18 #include "AP_Follow.h"
19 #include <ctype.h>
20 #include <stdio.h>
21 
22 extern const AP_HAL::HAL& hal;
23 
24 #define AP_FOLLOW_TIMEOUT_MS 3000 // position estimate timeout after 1 second
25 #define AP_FOLLOW_SYSID_TIMEOUT_MS 10000 // forget sysid we are following if we haave not heard from them in 10 seconds
26 #define AP_GCS_INTERVAL_MS 1000 // interval between updating GCS on position of vehicle
27 
28 #define AP_FOLLOW_OFFSET_TYPE_NED 0 // offsets are in north-east-down frame
29 #define AP_FOLLOW_OFFSET_TYPE_RELATIVE 0 // offsets are relative to lead vehicle's heading
30 
31 #define AP_FOLLOW_POS_P_DEFAULT 0.1f // position error gain default
32 
33 // table of user settable parameters
35 
36  // @Param: _ENABLE
37  // @DisplayName: Follow enable/disable
38  // @Description: Enabled/disable following a target
39  // @Values: 0:Disabled,1:Enabled
40  // @User: Standard
41  AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_Follow, _enabled, 0, AP_PARAM_FLAG_ENABLE),
42 
43  // 2 is reserved for TYPE parameter
44 
45  // @Param: _SYSID
46  // @DisplayName: Follow target's mavlink system id
47  // @Description: Follow target's mavlink system id
48  // @Range: 0 255
49  // @User: Standard
50  AP_GROUPINFO("_SYSID", 3, AP_Follow, _sysid, 0),
51 
52  // 4 is reserved for MARGIN parameter
53 
54  // @Param: _DIST_MAX
55  // @DisplayName: Follow distance maximum
56  // @Description: Follow distance maximum. targets further than this will be ignored
57  // @Units: m
58  // @Range: 1 1000
59  // @User: Standard
60  AP_GROUPINFO("_DIST_MAX", 5, AP_Follow, _dist_max, 100),
61 
62  // @Param: _OFS_TYPE
63  // @DisplayName: Follow offset type
64  // @Description: Follow offset type
65  // @Values: 0:North-East-Down, 1:Relative to lead vehicle heading
66  // @User: Standard
67  AP_GROUPINFO("_OFS_TYPE", 6, AP_Follow, _offset_type, AP_FOLLOW_OFFSET_TYPE_NED),
68 
69  // @Param: _OFS_X
70  // @DisplayName: Follow offsets in meters north/forward
71  // @Description: Follow offsets in meters north/forward. If positive, this vehicle fly ahead or north of lead vehicle. Depends on FOLL_OFS_TYPE
72  // @Range: -100 100
73  // @Units: m
74  // @Increment: 1
75  // @User: Standard
76 
77  // @Param: _OFS_Y
78  // @DisplayName: Follow offsets in meters east/right
79  // @Description: Follow offsets in meters east/right. If positive, this vehicle fly to the right or east of lead vehicle. Depends on FOLL_OFS_TYPE
80  // @Range: -100 100
81  // @Units: m
82  // @Increment: 1
83  // @User: Standard
84 
85  // @Param: _OFS_Z
86  // @DisplayName: Follow offsets in meters down
87  // @Description: Follow offsets in meters down. If positive, this vehicle fly below the lead vehicle
88  // @Range: -100 100
89  // @Units: m
90  // @Increment: 1
91  // @User: Standard
92  AP_GROUPINFO("_OFS", 7, AP_Follow, _offset, 0),
93 
94  // @Param: _YAW_BEHAVE
95  // @DisplayName: Follow yaw behaviour
96  // @Description: Follow yaw behaviour
97  // @Values: 0:None,1:Face Lead Vehicle,2:Same as Lead vehicle,3:Direction of Flight
98  // @User: Standard
99  AP_GROUPINFO("_YAW_BEHAVE", 8, AP_Follow, _yaw_behave, 1),
100 
101  // @Param: _POS_P
102  // @DisplayName: Follow position error P gain
103  // @Description: Follow position error P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller
104  // @Range: 0.01 1.00
105  // @Increment: 0.01
106  // @User: Standard
107  AP_SUBGROUPINFO(_p_pos, "_POS_", 9, AP_Follow, AC_P),
108 
110 };
111 
112 /*
113  The constructor also initialises the proximity sensor. Note that this
114  constructor is not called until detect() returns true, so we
115  already know that we should setup the proximity sensor
116 */
119 {
122 }
123 
124 // get target's estimated location
126 {
127  // exit immediately if not enabled
128  if (!_enabled) {
129  return false;
130  }
131 
132  // check for timeout
134  return false;
135  }
136 
137  // calculate time since last actual position update
138  const float dt = (AP_HAL::millis() - _last_location_update_ms) * 0.001f;
139 
140  // get velocity estimate
141  if (!get_velocity_ned(vel_ned, dt)) {
142  return false;
143  }
144 
145  // project the vehicle position
146  Location last_loc = _target_location;
147  location_offset(last_loc, vel_ned.x * dt, vel_ned.y * dt);
148  last_loc.alt -= vel_ned.z * 10.0f * dt; // convert m/s to cm/s, multiply by dt. minus because NED
149 
150  // return latest position estimate
151  loc = last_loc;
152  return true;
153 }
154 
155 // get distance vector to target (in meters) and target's velocity all in NED frame
156 bool AP_Follow::get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_with_offs, Vector3f &vel_ned)
157 {
158  // get our location
159  Location current_loc;
160  if (!AP::ahrs().get_position(current_loc)) {
161  return false;
162  }
163 
164  // get target location and velocity
165  Location target_loc;
166  Vector3f veh_vel;
167  if (!get_target_location_and_velocity(target_loc, veh_vel)) {
168  return false;
169  }
170 
171  // calculate difference
172  const Vector3f dist_vec = location_3d_diff_NED(current_loc, target_loc);
173 
174  // fail if too far
175  if (is_positive(_dist_max.get()) && (dist_vec.length() > _dist_max)) {
176  return false;
177  }
178 
179  // initialise offsets from distance vector if required
180  init_offsets_if_required(dist_vec);
181 
182  // get offsets
183  Vector3f offsets;
184  if (!get_offsets_ned(offsets)) {
185  return false;
186  }
187 
188  // return results
189  dist_ned = dist_vec;
190  dist_with_offs = dist_vec + offsets;
191  vel_ned = veh_vel;
192  return true;
193 }
194 
195 // get target's heading in degrees (0 = north, 90 = east)
196 bool AP_Follow::get_target_heading(float &heading) const
197 {
198  // exit immediately if not enabled
199  if (!_enabled) {
200  return false;
201  }
202 
203  // check for timeout
205  return false;
206  }
207 
208  // return latest heading estimate
209  heading = _target_heading;
210  return true;
211 }
212 
213 // handle mavlink DISTANCE_SENSOR messages
214 void AP_Follow::handle_msg(const mavlink_message_t &msg)
215 {
216  // exit immediately if not enabled
217  if (!_enabled) {
218  return;
219  }
220 
221  // skip our own messages
222  if (msg.sysid == mavlink_system.sysid) {
223  return;
224  }
225 
226  // skip message if not from our target
227  if ((_sysid_to_follow != 0) && (msg.sysid != _sysid_to_follow)) {
228  if (_sysid == 0) {
229  // maybe timeout who we were following...
231  _sysid_to_follow = 0;
232  }
233  }
234  return;
235  }
236 
237  // decode global-position-int message
238  if (msg.msgid == MAVLINK_MSG_ID_GLOBAL_POSITION_INT) {
239 
240  const uint32_t now = AP_HAL::millis();
241 
242  // get estimated location and velocity (for logging)
243  Location loc_estimate{};
244  Vector3f vel_estimate;
245  UNUSED_RESULT(get_target_location_and_velocity(loc_estimate, vel_estimate));
246 
247  // decode message
248  mavlink_global_position_int_t packet;
249  mavlink_msg_global_position_int_decode(&msg, &packet);
250 
251  // ignore message if lat and lon are (exactly) zero
252  if ((packet.lat == 0 && packet.lon == 0)) {
253  return;
254  }
255 
256  _target_location.lat = packet.lat;
257  _target_location.lng = packet.lon;
258  _target_location.alt = packet.alt / 10; // convert millimeters to cm
259  _target_velocity_ned.x = packet.vx * 0.01f; // velocity north
260  _target_velocity_ned.y = packet.vy * 0.01f; // velocity east
261  _target_velocity_ned.z = packet.vz * 0.01f; // velocity down
263  if (packet.hdg <= 36000) { // heading (UINT16_MAX if unknown)
264  _target_heading = packet.hdg * 0.01f; // convert centi-degrees to degrees
266  }
267  // initialise _sysid if zero to sender's id
268  if (_sysid_to_follow == 0) {
269  _sysid_to_follow = msg.sysid;
270  }
272  gcs().send_text(MAV_SEVERITY_INFO, "Foll: %u %ld %ld %4.2f\n",
273  (unsigned)_sysid_to_follow,
274  (long)_target_location.lat,
275  (long)_target_location.lng,
276  (double)(_target_location.alt * 0.01f)); // cm to m
277  }
278 
279  // log lead's estimated vs reported position
281  "TimeUS,Lat,Lon,Alt,VelX,VelY,VelZ,LatE,LonE,AltE", // labels
282  "sDUmnnnDUm", // units
283  "F--B000--B", // mults
284  "QLLifffLLi", // fmt
289  (double)_target_velocity_ned.x,
290  (double)_target_velocity_ned.y,
291  (double)_target_velocity_ned.z,
292  loc_estimate.lat,
293  loc_estimate.lng,
294  loc_estimate.alt
295  );
296  }
297 }
298 
299 // get velocity estimate in m/s in NED frame using dt since last update
300 bool AP_Follow::get_velocity_ned(Vector3f &vel_ned, float dt) const
301 {
302  vel_ned = _target_velocity_ned + (_target_accel_ned * dt);
303  return true;
304 }
305 
306 // initialise offsets to provided distance vector (in meters in NED frame) if required
308 {
309  if (_offset.get().is_zero()) {
310  _offset = dist_vec_ned;
311  }
312 }
313 
314 // get offsets in meters in NED frame
316 {
317  const Vector3f &off = _offset.get();
318 
319  // if offsets are zero or type if NED, simply return offset vector
320  if (off.is_zero() || (_offset_type == AP_FOLLOW_OFFSET_TYPE_NED)) {
321  offset = off;
322  return true;
323  }
324 
325  // offset_type == AP_FOLLOW_OFFSET_TYPE_RELATIVE
326  // check if we have a valid heading for target vehicle
328  return false;
329  }
330 
331  // rotate roll, pitch input from north facing to vehicle's perspective
332  const float veh_cos_yaw = cosf(radians(_target_heading));
333  const float veh_sin_yaw = sinf(radians(_target_heading));
334  offset.x = (off.x * veh_cos_yaw) - (off.y * veh_sin_yaw);
335  offset.y = (off.y * veh_cos_yaw) + (off.x * veh_sin_yaw);
336  offset.z = off.z;
337  return true;
338 }
#define AP_FOLLOW_POS_P_DEFAULT
Definition: AP_Follow.cpp:31
#define AP_FOLLOW_SYSID_TIMEOUT_MS
Definition: AP_Follow.cpp:25
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
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.
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
GCS & gcs()
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
Definition: location.cpp:125
#define AP_FOLLOW_OFFSET_TYPE_NED
Definition: AP_Follow.cpp:28
bool get_velocity_ned(Vector3f &vel_ned, float dt) const
Definition: AP_Follow.cpp:300
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
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
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
#define AP_GCS_INTERVAL_MS
Definition: AP_Follow.cpp:26
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
#define f(i)
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
uint64_t micros64()
Definition: system.cpp:162
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
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
#define UNUSED_RESULT(expr_)
Definition: AP_Common.h:104
#define AP_FOLLOW_TIMEOUT_MS
Definition: AP_Follow.cpp:24
#define off
Definition: Config.h:52
float length(void) const
Definition: vector3.cpp:288
AP_AHRS & ahrs()
Definition: AP_AHRS.cpp:488
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
Vector3f location_3d_diff_NED(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:149
static constexpr float radians(float deg)
Definition: AP_Math.h:158
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
bool is_zero(void) const
Definition: vector3.h:159
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
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
Location _target_location
Definition: AP_Follow.h:103
AP_Vector3f _offset
Definition: AP_Follow.h:95
#define AP_GROUPEND
Definition: AP_Param.h:121
void handle_msg(const mavlink_message_t &msg)
Definition: AP_Follow.cpp:214
T x
Definition: vector3.h:67
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214