ardupilot/ArduCopter/mode_follow.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

176 lines
6.8 KiB
C++
Raw Normal View History

2017-12-26 19:09:11 -04:00
#include "Copter.h"
#if MODE_FOLLOW_ENABLED == ENABLED
2017-12-26 19:09:11 -04:00
/*
2018-02-05 22:44:05 -04:00
* mode_follow.cpp - follow another mavlink-enabled vehicle by system id
2017-12-26 19:09:11 -04:00
*
* TODO: stick control to move around on sphere
* TODO: stick control to change sphere diameter
* TODO: "channel 7 option" to lock onto "pointed at" target
* TODO: do better in terms of loitering around the moving point; may need a PID? Maybe use loiter controller somehow?
* TODO: extrapolate target vehicle position using its velocity and acceleration
* TODO: ensure AC_AVOID_ENABLED is true because we rely on it velocity limiting functions
2017-12-26 19:09:11 -04:00
*/
// initialise follow mode
bool ModeFollow::init(const bool ignore_checks)
2017-12-26 19:09:11 -04:00
{
if (!g2.follow.enabled()) {
2018-12-08 00:18:41 -04:00
gcs().send_text(MAV_SEVERITY_WARNING, "Set FOLL_ENABLE = 1");
2017-12-26 19:09:11 -04:00
return false;
}
#if HAL_MOUNT_ENABLED
AP_Mount *mount = AP_Mount::get_singleton();
// follow the lead vehicle using sysid
if (g2.follow.option_is_enabled(AP_Follow::Option::MOUNT_FOLLOW_ON_ENTER) && mount != nullptr) {
mount->set_target_sysid(g2.follow.get_target_sysid());
}
#endif
2018-12-08 00:18:41 -04:00
// re-use guided mode
return ModeGuided::init(ignore_checks);
2017-12-26 19:09:11 -04:00
}
// perform cleanup required when leaving follow mode
void ModeFollow::exit()
{
g2.follow.clear_offsets_if_required();
}
void ModeFollow::run()
2017-12-26 19:09:11 -04:00
{
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if (is_disarmed_or_landed()) {
make_safe_ground_handling();
2017-12-26 19:09:11 -04:00
return;
}
// set motors to full range
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
2017-12-26 19:09:11 -04:00
// re-use guided mode's velocity controller
// Note: this is safe from interference from GCSs and companion computer's whose guided mode
// position and velocity requests will be ignored while the vehicle is not in guided mode
// variables to be sent to velocity controller
Vector3f desired_velocity_neu_cms;
bool use_yaw = false;
float yaw_cd = 0.0f;
Vector3f dist_vec; // vector to lead vehicle
Vector3f dist_vec_offs; // vector to lead vehicle + offset
Vector3f vel_of_target; // velocity of lead vehicle
if (g2.follow.get_target_dist_and_vel_ned(dist_vec, dist_vec_offs, vel_of_target)) {
// convert dist_vec_offs to cm in NEU
const Vector3f dist_vec_offs_neu(dist_vec_offs.x * 100.0f, dist_vec_offs.y * 100.0f, -dist_vec_offs.z * 100.0f);
// calculate desired relative velocity vector in cm/s in NEU
const float kp = g2.follow.get_pos_p().kP();
desired_velocity_neu_cms = dist_vec_offs_neu * kp;
2017-12-26 19:09:11 -04:00
// create horizontal desired velocity vector (required for slow down calculations)
Vector2f desired_velocity_xy_cms(desired_velocity_neu_cms.x, desired_velocity_neu_cms.y);
2017-12-26 19:09:11 -04:00
// create horizontal unit vector towards target (required for slow down calculations)
Vector2f dir_to_target_xy(desired_velocity_xy_cms.x, desired_velocity_xy_cms.y);
if (!dir_to_target_xy.is_zero()) {
dir_to_target_xy.normalize();
}
2017-12-26 19:09:11 -04:00
// slow down horizontally as we approach target (use 1/2 of maximum deceleration for gentle slow down)
const float dist_to_target_xy = Vector2f(dist_vec_offs_neu.x, dist_vec_offs_neu.y).length();
2021-05-11 01:42:02 -03:00
copter.avoid.limit_velocity_2D(pos_control->get_pos_xy_p().kP().get(), pos_control->get_max_accel_xy_cmss() * 0.5f, desired_velocity_xy_cms, dir_to_target_xy, dist_to_target_xy, copter.G_Dt);
// copy horizontal velocity limits back to 3d vector
desired_velocity_neu_cms.xy() = desired_velocity_xy_cms;
// limit vertical desired_velocity_neu_cms to slow as we approach target (we use 1/2 of maximum deceleration for gentle slow down)
2021-05-11 01:42:02 -03:00
const float des_vel_z_max = copter.avoid.get_max_speed(pos_control->get_pos_z_p().kP().get(), pos_control->get_max_accel_z_cmss() * 0.5f, fabsf(dist_vec_offs_neu.z), copter.G_Dt);
desired_velocity_neu_cms.z = constrain_float(desired_velocity_neu_cms.z, -des_vel_z_max, des_vel_z_max);
// Add the target velocity baseline.
desired_velocity_neu_cms.xy() += vel_of_target.xy() * 100.0f;
desired_velocity_neu_cms.z += -vel_of_target.z * 100.0f;
// scale desired velocity to stay within horizontal speed limit
desired_velocity_neu_cms.xy().limit_length(pos_control->get_max_speed_xy_cms());
// limit desired velocity to be between maximum climb and descent rates
desired_velocity_neu_cms.z = constrain_float(desired_velocity_neu_cms.z, -fabsf(pos_control->get_max_speed_down_cms()), pos_control->get_max_speed_up_cms());
2020-12-06 08:48:21 -04:00
// limit the velocity for obstacle/fence avoidance
2021-05-11 01:42:02 -03:00
copter.avoid.adjust_velocity(desired_velocity_neu_cms, pos_control->get_pos_xy_p().kP().get(), pos_control->get_max_accel_xy_cmss(), pos_control->get_pos_z_p().kP().get(), pos_control->get_max_accel_z_cmss(), G_Dt);
// calculate vehicle heading
switch (g2.follow.get_yaw_behave()) {
case AP_Follow::YAW_BEHAVE_FACE_LEAD_VEHICLE: {
2021-10-20 05:29:57 -03:00
if (dist_vec.xy().length_squared() > 1.0) {
yaw_cd = get_bearing_cd(Vector2f{}, dist_vec.xy());
use_yaw = true;
}
break;
}
case AP_Follow::YAW_BEHAVE_SAME_AS_LEAD_VEHICLE: {
float target_hdg = 0.0f;
if (g2.follow.get_target_heading_deg(target_hdg)) {
yaw_cd = target_hdg * 100.0f;
use_yaw = true;
}
break;
}
case AP_Follow::YAW_BEHAVE_DIR_OF_FLIGHT: {
2021-10-20 05:29:57 -03:00
if (desired_velocity_neu_cms.xy().length_squared() > (100.0 * 100.0)) {
yaw_cd = get_bearing_cd(Vector2f{}, desired_velocity_neu_cms.xy());
use_yaw = true;
}
break;
}
case AP_Follow::YAW_BEHAVE_NONE:
default:
// do nothing
break;
2017-12-26 19:09:11 -04:00
}
2017-12-26 19:09:11 -04:00
}
// log output at 10hz
uint32_t now = AP_HAL::millis();
bool log_request = false;
if ((now - last_log_ms >= 100) || (last_log_ms == 0)) {
log_request = true;
last_log_ms = now;
}
// re-use guided mode's velocity controller (takes NEU)
ModeGuided::set_velocity(desired_velocity_neu_cms, use_yaw, yaw_cd, false, 0.0f, false, log_request);
2017-12-26 19:09:11 -04:00
ModeGuided::run();
2017-12-26 19:09:11 -04:00
}
uint32_t ModeFollow::wp_distance() const
{
return g2.follow.get_distance_to_target() * 100;
}
int32_t ModeFollow::wp_bearing() const
{
return g2.follow.get_bearing_to_target() * 100;
}
/*
get target position for mavlink reporting
*/
2021-07-06 18:02:26 -03:00
bool ModeFollow::get_wp(Location &loc) const
{
float dist = g2.follow.get_distance_to_target();
float bearing = g2.follow.get_bearing_to_target();
loc = copter.current_loc;
loc.offset_bearing(bearing, dist);
return true;
}
#endif // MODE_FOLLOW_ENABLED == ENABLED