123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394 |
- #include <AP_HAL/AP_HAL.h>
- #include "AP_Follow.h"
- #include <ctype.h>
- #include <stdio.h>
- #include <AP_AHRS/AP_AHRS.h>
- #include <AP_Logger/AP_Logger.h>
- extern const AP_HAL::HAL& hal;
- #define AP_FOLLOW_TIMEOUT_MS 3000
- #define AP_FOLLOW_SYSID_TIMEOUT_MS 10000
- #define AP_FOLLOW_OFFSET_TYPE_NED 0
- #define AP_FOLLOW_OFFSET_TYPE_RELATIVE 1
- #define AP_FOLLOW_ALTITUDE_TYPE_RELATIVE 1
- #define AP_FOLLOW_POS_P_DEFAULT 0.1f
- const AP_Param::GroupInfo AP_Follow::var_info[] = {
-
-
-
-
-
- AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_Follow, _enabled, 0, AP_PARAM_FLAG_ENABLE),
-
-
-
-
-
-
- AP_GROUPINFO("_SYSID", 3, AP_Follow, _sysid, 0),
-
-
-
-
-
-
-
- AP_GROUPINFO("_DIST_MAX", 5, AP_Follow, _dist_max, 100),
-
-
-
-
-
- AP_GROUPINFO("_OFS_TYPE", 6, AP_Follow, _offset_type, AP_FOLLOW_OFFSET_TYPE_NED),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("_OFS", 7, AP_Follow, _offset, 0),
-
-
-
-
-
- AP_GROUPINFO("_YAW_BEHAVE", 8, AP_Follow, _yaw_behave, 1),
-
-
-
-
-
-
- AP_SUBGROUPINFO(_p_pos, "_POS_", 9, AP_Follow, AC_P),
-
-
-
-
-
- AP_GROUPINFO("_ALT_TYPE", 10, AP_Follow, _alt_type, AP_FOLLOW_ALTITUDE_TYPE_RELATIVE),
- AP_GROUPEND
- };
- AP_Follow::AP_Follow() :
- _p_pos(AP_FOLLOW_POS_P_DEFAULT)
- {
- AP_Param::setup_object_defaults(this, var_info);
- }
- bool AP_Follow::get_target_location_and_velocity(Location &loc, Vector3f &vel_ned) const
- {
-
- if (!_enabled) {
- return false;
- }
-
- if ((_last_location_update_ms == 0) || (AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_TIMEOUT_MS)) {
- return false;
- }
-
- const float dt = (AP_HAL::millis() - _last_location_update_ms) * 0.001f;
-
- if (!get_velocity_ned(vel_ned, dt)) {
- return false;
- }
-
- Location last_loc = _target_location;
- last_loc.offset(vel_ned.x * dt, vel_ned.y * dt);
- last_loc.alt -= vel_ned.z * 100.0f * dt;
-
- loc = last_loc;
- return true;
- }
- bool AP_Follow::get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_with_offs, Vector3f &vel_ned)
- {
-
- Location current_loc;
- if (!AP::ahrs().get_position(current_loc)) {
- clear_dist_and_bearing_to_target();
- return false;
- }
-
- Location target_loc;
- Vector3f veh_vel;
- if (!get_target_location_and_velocity(target_loc, veh_vel)) {
- clear_dist_and_bearing_to_target();
- return false;
- }
-
- if (target_loc.relative_alt == 1) {
- current_loc.alt -= AP::ahrs().get_home().alt;
- }
-
- const Vector3f dist_vec = current_loc.get_distance_NED(target_loc);
-
- if (is_positive(_dist_max.get()) && (dist_vec.length() > _dist_max)) {
- clear_dist_and_bearing_to_target();
- return false;
- }
-
- init_offsets_if_required(dist_vec);
-
- Vector3f offsets;
- if (!get_offsets_ned(offsets)) {
- clear_dist_and_bearing_to_target();
- return false;
- }
-
- dist_ned = dist_vec;
- dist_with_offs = dist_vec + offsets;
- vel_ned = veh_vel;
-
- if (is_zero(dist_with_offs.x) && is_zero(dist_with_offs.y)) {
- clear_dist_and_bearing_to_target();
- } else {
- _dist_to_target = safe_sqrt(sq(dist_with_offs.x) + sq(dist_with_offs.y));
- _bearing_to_target = degrees(atan2f(dist_with_offs.y, dist_with_offs.x));
- }
- return true;
- }
- bool AP_Follow::get_target_heading_deg(float &heading) const
- {
-
- if (!_enabled) {
- return false;
- }
-
- if ((_last_heading_update_ms == 0) || (AP_HAL::millis() - _last_heading_update_ms > AP_FOLLOW_TIMEOUT_MS)) {
- return false;
- }
-
- heading = _target_heading;
- return true;
- }
- void AP_Follow::handle_msg(const mavlink_message_t &msg)
- {
-
- if (!_enabled) {
- return;
- }
-
- if (msg.sysid == mavlink_system.sysid) {
- return;
- }
-
- if (_sysid != 0 && msg.sysid != _sysid) {
- if (_automatic_sysid) {
-
- if ((_last_location_update_ms == 0) || (AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_SYSID_TIMEOUT_MS)) {
- _sysid.set(0);
- }
- }
- return;
- }
-
- if (msg.msgid == MAVLINK_MSG_ID_GLOBAL_POSITION_INT) {
-
- Location loc_estimate{};
- Vector3f vel_estimate;
- UNUSED_RESULT(get_target_location_and_velocity(loc_estimate, vel_estimate));
-
- mavlink_global_position_int_t packet;
- mavlink_msg_global_position_int_decode(&msg, &packet);
-
- if ((packet.lat == 0 && packet.lon == 0)) {
- return;
- }
- _target_location.lat = packet.lat;
- _target_location.lng = packet.lon;
-
- if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE) {
-
- _target_location.alt = packet.relative_alt / 10;
- _target_location.relative_alt = 1;
- } else {
-
- _target_location.alt = packet.alt / 10;
- _target_location.relative_alt = 0;
- }
- _target_velocity_ned.x = packet.vx * 0.01f;
- _target_velocity_ned.y = packet.vy * 0.01f;
- _target_velocity_ned.z = packet.vz * 0.01f;
-
- _last_location_update_ms = _jitter.correct_offboard_timestamp_msec(packet.time_boot_ms, AP_HAL::millis());
- if (packet.hdg <= 36000) {
- _target_heading = packet.hdg * 0.01f;
- _last_heading_update_ms = _last_location_update_ms;
- }
-
- if (_sysid == 0) {
- _sysid.set(msg.sysid);
- _automatic_sysid = true;
- }
-
- AP::logger().Write("FOLL",
- "TimeUS,Lat,Lon,Alt,VelN,VelE,VelD,LatE,LonE,AltE",
- "sDUmnnnDUm",
- "F--B000--B",
- "QLLifffLLi",
- AP_HAL::micros64(),
- _target_location.lat,
- _target_location.lng,
- _target_location.alt,
- (double)_target_velocity_ned.x,
- (double)_target_velocity_ned.y,
- (double)_target_velocity_ned.z,
- loc_estimate.lat,
- loc_estimate.lng,
- loc_estimate.alt
- );
- }
- }
- bool AP_Follow::get_velocity_ned(Vector3f &vel_ned, float dt) const
- {
- vel_ned = _target_velocity_ned + (_target_accel_ned * dt);
- return true;
- }
- void AP_Follow::init_offsets_if_required(const Vector3f &dist_vec_ned)
- {
-
- if (!_offset.get().is_zero()) {
- return;
- }
- float target_heading_deg;
- if ((_offset_type == AP_FOLLOW_OFFSET_TYPE_RELATIVE) && get_target_heading_deg(target_heading_deg)) {
-
- _offset = rotate_vector(-dist_vec_ned, -target_heading_deg);
- } else {
-
- _offset = -dist_vec_ned;
-
- _offset_type = AP_FOLLOW_OFFSET_TYPE_NED;
- }
- }
- bool AP_Follow::get_offsets_ned(Vector3f &offset) const
- {
- const Vector3f &off = _offset.get();
-
- if (off.is_zero() || (_offset_type == AP_FOLLOW_OFFSET_TYPE_NED)) {
- offset = off;
- return true;
- }
-
- float target_heading_deg;
- if (!get_target_heading_deg(target_heading_deg)) {
- return false;
- }
-
- offset = rotate_vector(off, target_heading_deg);
- return true;
- }
- Vector3f AP_Follow::rotate_vector(const Vector3f &vec, float angle_deg) const
- {
-
- const float cos_yaw = cosf(radians(angle_deg));
- const float sin_yaw = sinf(radians(angle_deg));
- return Vector3f((vec.x * cos_yaw) - (vec.y * sin_yaw), (vec.y * cos_yaw) + (vec.x * sin_yaw), vec.z);
- }
- void AP_Follow::clear_dist_and_bearing_to_target()
- {
- _dist_to_target = 0.0f;
- _bearing_to_target = 0.0f;
- }
|