AP_Follow.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394
  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. #include <AP_HAL/AP_HAL.h>
  14. #include "AP_Follow.h"
  15. #include <ctype.h>
  16. #include <stdio.h>
  17. #include <AP_AHRS/AP_AHRS.h>
  18. #include <AP_Logger/AP_Logger.h>
  19. extern const AP_HAL::HAL& hal;
  20. #define AP_FOLLOW_TIMEOUT_MS 3000 // position estimate timeout after 1 second
  21. #define AP_FOLLOW_SYSID_TIMEOUT_MS 10000 // forget sysid we are following if we haave not heard from them in 10 seconds
  22. #define AP_FOLLOW_OFFSET_TYPE_NED 0 // offsets are in north-east-down frame
  23. #define AP_FOLLOW_OFFSET_TYPE_RELATIVE 1 // offsets are relative to lead vehicle's heading
  24. #define AP_FOLLOW_ALTITUDE_TYPE_RELATIVE 1 // relative altitude is used by default
  25. #define AP_FOLLOW_POS_P_DEFAULT 0.1f // position error gain default
  26. // table of user settable parameters
  27. const AP_Param::GroupInfo AP_Follow::var_info[] = {
  28. // @Param: _ENABLE
  29. // @DisplayName: Follow enable/disable
  30. // @Description: Enabled/disable following a target
  31. // @Values: 0:Disabled,1:Enabled
  32. // @User: Standard
  33. AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_Follow, _enabled, 0, AP_PARAM_FLAG_ENABLE),
  34. // 2 is reserved for TYPE parameter
  35. // @Param: _SYSID
  36. // @DisplayName: Follow target's mavlink system id
  37. // @Description: Follow target's mavlink system id
  38. // @Range: 0 255
  39. // @User: Standard
  40. AP_GROUPINFO("_SYSID", 3, AP_Follow, _sysid, 0),
  41. // 4 is reserved for MARGIN parameter
  42. // @Param: _DIST_MAX
  43. // @DisplayName: Follow distance maximum
  44. // @Description: Follow distance maximum. targets further than this will be ignored
  45. // @Units: m
  46. // @Range: 1 1000
  47. // @User: Standard
  48. AP_GROUPINFO("_DIST_MAX", 5, AP_Follow, _dist_max, 100),
  49. // @Param: _OFS_TYPE
  50. // @DisplayName: Follow offset type
  51. // @Description: Follow offset type
  52. // @Values: 0:North-East-Down, 1:Relative to lead vehicle heading
  53. // @User: Standard
  54. AP_GROUPINFO("_OFS_TYPE", 6, AP_Follow, _offset_type, AP_FOLLOW_OFFSET_TYPE_NED),
  55. // @Param: _OFS_X
  56. // @DisplayName: Follow offsets in meters north/forward
  57. // @Description: Follow offsets in meters north/forward. If positive, this vehicle fly ahead or north of lead vehicle. Depends on FOLL_OFS_TYPE
  58. // @Range: -100 100
  59. // @Units: m
  60. // @Increment: 1
  61. // @User: Standard
  62. // @Param: _OFS_Y
  63. // @DisplayName: Follow offsets in meters east/right
  64. // @Description: Follow offsets in meters east/right. If positive, this vehicle will fly to the right or east of lead vehicle. Depends on FOLL_OFS_TYPE
  65. // @Range: -100 100
  66. // @Units: m
  67. // @Increment: 1
  68. // @User: Standard
  69. // @Param: _OFS_Z
  70. // @DisplayName: Follow offsets in meters down
  71. // @Description: Follow offsets in meters down. If positive, this vehicle will fly below the lead vehicle
  72. // @Range: -100 100
  73. // @Units: m
  74. // @Increment: 1
  75. // @User: Standard
  76. AP_GROUPINFO("_OFS", 7, AP_Follow, _offset, 0),
  77. // @Param: _YAW_BEHAVE
  78. // @DisplayName: Follow yaw behaviour
  79. // @Description: Follow yaw behaviour
  80. // @Values: 0:None,1:Face Lead Vehicle,2:Same as Lead vehicle,3:Direction of Flight
  81. // @User: Standard
  82. AP_GROUPINFO("_YAW_BEHAVE", 8, AP_Follow, _yaw_behave, 1),
  83. // @Param: _POS_P
  84. // @DisplayName: Follow position error P gain
  85. // @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
  86. // @Range: 0.01 1.00
  87. // @Increment: 0.01
  88. // @User: Standard
  89. AP_SUBGROUPINFO(_p_pos, "_POS_", 9, AP_Follow, AC_P),
  90. // @Param: _ALT_TYPE
  91. // @DisplayName: Follow altitude type
  92. // @Description: Follow altitude type
  93. // @Values: 0:absolute, 1: relative
  94. // @User: Standard
  95. AP_GROUPINFO("_ALT_TYPE", 10, AP_Follow, _alt_type, AP_FOLLOW_ALTITUDE_TYPE_RELATIVE),
  96. AP_GROUPEND
  97. };
  98. /*
  99. The constructor also initialises the proximity sensor. Note that this
  100. constructor is not called until detect() returns true, so we
  101. already know that we should setup the proximity sensor
  102. */
  103. AP_Follow::AP_Follow() :
  104. _p_pos(AP_FOLLOW_POS_P_DEFAULT)
  105. {
  106. AP_Param::setup_object_defaults(this, var_info);
  107. }
  108. // get target's estimated location
  109. bool AP_Follow::get_target_location_and_velocity(Location &loc, Vector3f &vel_ned) const
  110. {
  111. // exit immediately if not enabled
  112. if (!_enabled) {
  113. return false;
  114. }
  115. // check for timeout
  116. if ((_last_location_update_ms == 0) || (AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_TIMEOUT_MS)) {
  117. return false;
  118. }
  119. // calculate time since last actual position update
  120. const float dt = (AP_HAL::millis() - _last_location_update_ms) * 0.001f;
  121. // get velocity estimate
  122. if (!get_velocity_ned(vel_ned, dt)) {
  123. return false;
  124. }
  125. // project the vehicle position
  126. Location last_loc = _target_location;
  127. last_loc.offset(vel_ned.x * dt, vel_ned.y * dt);
  128. last_loc.alt -= vel_ned.z * 100.0f * dt; // convert m/s to cm/s, multiply by dt. minus because NED
  129. // return latest position estimate
  130. loc = last_loc;
  131. return true;
  132. }
  133. // get distance vector to target (in meters) and target's velocity all in NED frame
  134. bool AP_Follow::get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_with_offs, Vector3f &vel_ned)
  135. {
  136. // get our location
  137. Location current_loc;
  138. if (!AP::ahrs().get_position(current_loc)) {
  139. clear_dist_and_bearing_to_target();
  140. return false;
  141. }
  142. // get target location and velocity
  143. Location target_loc;
  144. Vector3f veh_vel;
  145. if (!get_target_location_and_velocity(target_loc, veh_vel)) {
  146. clear_dist_and_bearing_to_target();
  147. return false;
  148. }
  149. // change to altitude above home if relative altitude is being used
  150. if (target_loc.relative_alt == 1) {
  151. current_loc.alt -= AP::ahrs().get_home().alt;
  152. }
  153. // calculate difference
  154. const Vector3f dist_vec = current_loc.get_distance_NED(target_loc);
  155. // fail if too far
  156. if (is_positive(_dist_max.get()) && (dist_vec.length() > _dist_max)) {
  157. clear_dist_and_bearing_to_target();
  158. return false;
  159. }
  160. // initialise offsets from distance vector if required
  161. init_offsets_if_required(dist_vec);
  162. // get offsets
  163. Vector3f offsets;
  164. if (!get_offsets_ned(offsets)) {
  165. clear_dist_and_bearing_to_target();
  166. return false;
  167. }
  168. // calculate results
  169. dist_ned = dist_vec;
  170. dist_with_offs = dist_vec + offsets;
  171. vel_ned = veh_vel;
  172. // record distance and heading for reporting purposes
  173. if (is_zero(dist_with_offs.x) && is_zero(dist_with_offs.y)) {
  174. clear_dist_and_bearing_to_target();
  175. } else {
  176. _dist_to_target = safe_sqrt(sq(dist_with_offs.x) + sq(dist_with_offs.y));
  177. _bearing_to_target = degrees(atan2f(dist_with_offs.y, dist_with_offs.x));
  178. }
  179. return true;
  180. }
  181. // get target's heading in degrees (0 = north, 90 = east)
  182. bool AP_Follow::get_target_heading_deg(float &heading) const
  183. {
  184. // exit immediately if not enabled
  185. if (!_enabled) {
  186. return false;
  187. }
  188. // check for timeout
  189. if ((_last_heading_update_ms == 0) || (AP_HAL::millis() - _last_heading_update_ms > AP_FOLLOW_TIMEOUT_MS)) {
  190. return false;
  191. }
  192. // return latest heading estimate
  193. heading = _target_heading;
  194. return true;
  195. }
  196. // handle mavlink DISTANCE_SENSOR messages
  197. void AP_Follow::handle_msg(const mavlink_message_t &msg)
  198. {
  199. // exit immediately if not enabled
  200. if (!_enabled) {
  201. return;
  202. }
  203. // skip our own messages
  204. if (msg.sysid == mavlink_system.sysid) {
  205. return;
  206. }
  207. // skip message if not from our target
  208. if (_sysid != 0 && msg.sysid != _sysid) {
  209. if (_automatic_sysid) {
  210. // maybe timeout who we were following...
  211. if ((_last_location_update_ms == 0) || (AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_SYSID_TIMEOUT_MS)) {
  212. _sysid.set(0);
  213. }
  214. }
  215. return;
  216. }
  217. // decode global-position-int message
  218. if (msg.msgid == MAVLINK_MSG_ID_GLOBAL_POSITION_INT) {
  219. // get estimated location and velocity (for logging)
  220. Location loc_estimate{};
  221. Vector3f vel_estimate;
  222. UNUSED_RESULT(get_target_location_and_velocity(loc_estimate, vel_estimate));
  223. // decode message
  224. mavlink_global_position_int_t packet;
  225. mavlink_msg_global_position_int_decode(&msg, &packet);
  226. // ignore message if lat and lon are (exactly) zero
  227. if ((packet.lat == 0 && packet.lon == 0)) {
  228. return;
  229. }
  230. _target_location.lat = packet.lat;
  231. _target_location.lng = packet.lon;
  232. // select altitude source based on FOLL_ALT_TYPE param
  233. if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE) {
  234. // relative altitude
  235. _target_location.alt = packet.relative_alt / 10; // convert millimeters to cm
  236. _target_location.relative_alt = 1; // set relative_alt flag
  237. } else {
  238. // absolute altitude
  239. _target_location.alt = packet.alt / 10; // convert millimeters to cm
  240. _target_location.relative_alt = 0; // reset relative_alt flag
  241. }
  242. _target_velocity_ned.x = packet.vx * 0.01f; // velocity north
  243. _target_velocity_ned.y = packet.vy * 0.01f; // velocity east
  244. _target_velocity_ned.z = packet.vz * 0.01f; // velocity down
  245. // get a local timestamp with correction for transport jitter
  246. _last_location_update_ms = _jitter.correct_offboard_timestamp_msec(packet.time_boot_ms, AP_HAL::millis());
  247. if (packet.hdg <= 36000) { // heading (UINT16_MAX if unknown)
  248. _target_heading = packet.hdg * 0.01f; // convert centi-degrees to degrees
  249. _last_heading_update_ms = _last_location_update_ms;
  250. }
  251. // initialise _sysid if zero to sender's id
  252. if (_sysid == 0) {
  253. _sysid.set(msg.sysid);
  254. _automatic_sysid = true;
  255. }
  256. // log lead's estimated vs reported position
  257. AP::logger().Write("FOLL",
  258. "TimeUS,Lat,Lon,Alt,VelN,VelE,VelD,LatE,LonE,AltE", // labels
  259. "sDUmnnnDUm", // units
  260. "F--B000--B", // mults
  261. "QLLifffLLi", // fmt
  262. AP_HAL::micros64(),
  263. _target_location.lat,
  264. _target_location.lng,
  265. _target_location.alt,
  266. (double)_target_velocity_ned.x,
  267. (double)_target_velocity_ned.y,
  268. (double)_target_velocity_ned.z,
  269. loc_estimate.lat,
  270. loc_estimate.lng,
  271. loc_estimate.alt
  272. );
  273. }
  274. }
  275. // get velocity estimate in m/s in NED frame using dt since last update
  276. bool AP_Follow::get_velocity_ned(Vector3f &vel_ned, float dt) const
  277. {
  278. vel_ned = _target_velocity_ned + (_target_accel_ned * dt);
  279. return true;
  280. }
  281. // initialise offsets to provided distance vector to other vehicle (in meters in NED frame) if required
  282. void AP_Follow::init_offsets_if_required(const Vector3f &dist_vec_ned)
  283. {
  284. // return immediately if offsets have already been set
  285. if (!_offset.get().is_zero()) {
  286. return;
  287. }
  288. float target_heading_deg;
  289. if ((_offset_type == AP_FOLLOW_OFFSET_TYPE_RELATIVE) && get_target_heading_deg(target_heading_deg)) {
  290. // rotate offsets from north facing to vehicle's perspective
  291. _offset = rotate_vector(-dist_vec_ned, -target_heading_deg);
  292. } else {
  293. // initialise offset in NED frame
  294. _offset = -dist_vec_ned;
  295. // ensure offset_type used matches frame of offsets saved
  296. _offset_type = AP_FOLLOW_OFFSET_TYPE_NED;
  297. }
  298. }
  299. // get offsets in meters in NED frame
  300. bool AP_Follow::get_offsets_ned(Vector3f &offset) const
  301. {
  302. const Vector3f &off = _offset.get();
  303. // if offsets are zero or type is NED, simply return offset vector
  304. if (off.is_zero() || (_offset_type == AP_FOLLOW_OFFSET_TYPE_NED)) {
  305. offset = off;
  306. return true;
  307. }
  308. // offset type is relative, exit if we cannot get vehicle's heading
  309. float target_heading_deg;
  310. if (!get_target_heading_deg(target_heading_deg)) {
  311. return false;
  312. }
  313. // rotate offsets from vehicle's perspective to NED
  314. offset = rotate_vector(off, target_heading_deg);
  315. return true;
  316. }
  317. // rotate 3D vector clockwise by specified angle (in degrees)
  318. Vector3f AP_Follow::rotate_vector(const Vector3f &vec, float angle_deg) const
  319. {
  320. // rotate roll, pitch input from north facing to vehicle's perspective
  321. const float cos_yaw = cosf(radians(angle_deg));
  322. const float sin_yaw = sinf(radians(angle_deg));
  323. return Vector3f((vec.x * cos_yaw) - (vec.y * sin_yaw), (vec.y * cos_yaw) + (vec.x * sin_yaw), vec.z);
  324. }
  325. // set recorded distance and bearing to target to zero
  326. void AP_Follow::clear_dist_and_bearing_to_target()
  327. {
  328. _dist_to_target = 0.0f;
  329. _bearing_to_target = 0.0f;
  330. }