APM:Copter
mode_follow.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #if MODE_FOLLOW_ENABLED == ENABLED
4 
5 /*
6  * mode_follow.cpp - follow another mavlink-enabled vehicle by system id
7  *
8  * TODO: stick control to move around on sphere
9  * TODO: stick control to change sphere diameter
10  * TODO: "channel 7 option" to lock onto "pointed at" target
11  * TODO: do better in terms of loitering around the moving point; may need a PID? Maybe use loiter controller somehow?
12  * TODO: extrapolate target vehicle position using its velocity and acceleration
13  * TODO: ensure AC_AVOID_ENABLED is true because we rely on it velocity limiting functions
14  */
15 
16 #if 1
17 #define Debug(fmt, args ...) do { \
18  gcs().send_text(MAV_SEVERITY_WARNING, fmt, ## args); \
19  } while(0)
20 #elif 0
21 #define Debug(fmt, args ...) do { \
22  ::fprintf(stderr, "%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args);
23 #else
24 #define Debug(fmt, args ...)
25 #endif
26 
27 // initialise follow mode
28 bool Copter::ModeFollow::init(const bool ignore_checks)
29 {
30  // re-use guided mode
31  gcs().send_text(MAV_SEVERITY_WARNING, "Follow-mode init");
32  if (!g2.follow.enabled()) {
33  return false;
34  }
35  return Copter::ModeGuided::init(ignore_checks);
36 }
37 
39 {
40  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
41  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
43  return;
44  }
45 
46  // re-use guided mode's velocity controller
47  // Note: this is safe from interference from GCSs and companion computer's whose guided mode
48  // position and velocity requests will be ignored while the vehicle is not in guided mode
49 
50  // variables to be sent to velocity controller
51  Vector3f desired_velocity_neu_cms;
52  bool use_yaw = false;
53  float yaw_cd = 0.0f;
54 
55  Vector3f dist_vec; // vector to lead vehicle
56  Vector3f dist_vec_offs; // vector to lead vehicle + offset
57  Vector3f vel_of_target; // velocity of lead vehicle
58  if (g2.follow.get_target_dist_and_vel_ned(dist_vec, dist_vec_offs, vel_of_target)) {
59  // debug
60  static uint16_t counter = 0;
61  counter++;
62  if (counter >= 400) {
63  counter = 0;
64  Debug("dist to veh: %f %f %f", (double)dist_vec.x, (double)dist_vec.y, (double)dist_vec.z);
65  }
66 
67  // convert dist_vec_offs to cm in NEU
68  const Vector3f dist_vec_offs_neu(dist_vec_offs.x * 100.0f, dist_vec_offs.y * 100.0f, -dist_vec_offs.z * 100.0f);
69 
70  // calculate desired velocity vector in cm/s in NEU
71  const float kp = g2.follow.get_pos_p().kP();
72  desired_velocity_neu_cms.x = (vel_of_target.x * 100.0f) + (dist_vec_offs_neu.x * kp);
73  desired_velocity_neu_cms.y = (vel_of_target.y * 100.0f) + (dist_vec_offs_neu.y * kp);
74  desired_velocity_neu_cms.z = (-vel_of_target.z * 100.0f) + (dist_vec_offs_neu.z * kp);
75 
76  // scale desired velocity to stay within horizontal speed limit
77  float desired_speed_xy = safe_sqrt(sq(desired_velocity_neu_cms.x) + sq(desired_velocity_neu_cms.y));
78  if (!is_zero(desired_speed_xy) && (desired_speed_xy > pos_control->get_speed_xy())) {
79  const float scalar_xy = pos_control->get_speed_xy() / desired_speed_xy;
80  desired_velocity_neu_cms.x *= scalar_xy;
81  desired_velocity_neu_cms.y *= scalar_xy;
82  desired_speed_xy = pos_control->get_speed_xy();
83  }
84 
85  // limit desired velocity to be between maximum climb and descent rates
86  desired_velocity_neu_cms.z = constrain_float(desired_velocity_neu_cms.z, -fabsf(pos_control->get_speed_down()), pos_control->get_speed_up());
87 
88  // unit vector towards target position (i.e. vector to lead vehicle + offset)
89  Vector3f dir_to_target_neu = dist_vec_offs_neu;
90  const float dir_to_target_neu_len = dir_to_target_neu.length();
91  if (!is_zero(dir_to_target_neu_len)) {
92  dir_to_target_neu /= dir_to_target_neu_len;
93  }
94 
95  // create horizontal desired velocity vector (required for slow down calculations)
96  Vector2f desired_velocity_xy_cms(desired_velocity_neu_cms.x, desired_velocity_neu_cms.y);
97 
98  // create horizontal unit vector towards target (required for slow down calculations)
99  Vector2f dir_to_target_xy(desired_velocity_xy_cms.x, desired_velocity_xy_cms.y);
100  if (!dir_to_target_xy.is_zero()) {
101  dir_to_target_xy.normalize();
102  }
103 
104  // slow down horizontally as we approach target (use 1/2 of maximum deceleration for gentle slow down)
105  const float dist_to_target_xy = Vector2f(dist_vec_offs_neu.x, dist_vec_offs_neu.y).length();
106  copter.avoid.limit_velocity(pos_control->get_pos_xy_p().kP().get(), pos_control->get_accel_xy() * 0.5f, desired_velocity_xy_cms, dir_to_target_xy, dist_to_target_xy, copter.G_Dt);
107 
108  // limit the horizontal velocity to prevent fence violations
109  copter.avoid.adjust_velocity(pos_control->get_pos_xy_p().kP().get(), pos_control->get_accel_xy(), desired_velocity_xy_cms, G_Dt);
110 
111  // copy horizontal velocity limits back to 3d vector
112  desired_velocity_neu_cms.x = desired_velocity_xy_cms.x;
113  desired_velocity_neu_cms.y = desired_velocity_xy_cms.y;
114 
115  // limit vertical desired_velocity_neu_cms to slow as we approach target (we use 1/2 of maximum deceleration for gentle slow down)
116  const float des_vel_z_max = copter.avoid.get_max_speed(pos_control->get_pos_z_p().kP().get(), pos_control->get_accel_z() * 0.5f, fabsf(dist_vec_offs_neu.z), copter.G_Dt);
117  desired_velocity_neu_cms.z = constrain_float(desired_velocity_neu_cms.z, -des_vel_z_max, des_vel_z_max);
118 
119  // get avoidance adjusted climb rate
120  desired_velocity_neu_cms.z = get_avoidance_adjusted_climbrate(desired_velocity_neu_cms.z);
121 
122  // calculate vehicle heading
123  switch (g2.follow.get_yaw_behave()) {
125  const Vector3f dist_vec_xy(dist_vec.x, dist_vec.y, 0.0f);
126  if (dist_vec_xy.length() > 1.0f) {
127  yaw_cd = get_bearing_cd(Vector3f(), dist_vec_xy);
128  use_yaw = true;
129  }
130  break;
131  }
132 
134  float target_hdg = 0.0f;
135  if (g2.follow.get_target_heading(target_hdg)) {
136  yaw_cd = target_hdg * 100.0f;
137  use_yaw = true;
138  }
139  break;
140  }
141 
143  const Vector3f vel_vec(desired_velocity_neu_cms.x, desired_velocity_neu_cms.y, 0.0f);
144  if (vel_vec.length() > 100.0f) {
145  yaw_cd = get_bearing_cd(Vector3f(), vel_vec);
146  use_yaw = true;
147  }
148  break;
149  }
150 
152  default:
153  // do nothing
154  break;
155 
156  }
157  }
158 
159  // log output at 10hz
160  uint32_t now = AP_HAL::millis();
161  bool log_request = false;
162  if ((now - last_log_ms >= 100) || (last_log_ms == 0)) {
163  log_request = true;
164  last_log_ms = now;
165  }
166  // re-use guided mode's velocity controller (takes NEU)
167  Copter::ModeGuided::set_velocity(desired_velocity_neu_cms, use_yaw, yaw_cd, false, 0.0f, false, log_request);
168 
170 }
171 
172 #endif // MODE_FOLLOW_ENABLED == ENABLED
AP_Follow follow
Definition: Parameters.h:596
YAW_BEHAVE_SAME_AS_LEAD_VEHICLE
float get_speed_xy() const
void zero_throttle_and_relax_ac()
Definition: mode.cpp:373
float safe_sqrt(const T v)
bool get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_with_ofs, Vector3f &vel_ned)
AC_P & get_pos_xy_p()
float get_avoidance_adjusted_climbrate(float target_rate)
Definition: mode.cpp:617
GCS_Copter & gcs()
Definition: mode.cpp:587
YawBehave get_yaw_behave() const
uint32_t last_log_ms
Definition: Copter.h:1195
void run() override
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
void set_velocity(const Vector3f &velocity, bool use_yaw=false, float yaw_cd=0.0, bool use_yaw_rate=false, float yaw_rate_cds=0.0, bool yaw_relative=false, bool log_request=true)
float get_accel_xy() const
#define Debug(fmt, args ...)
Definition: mode_follow.cpp:17
float get_speed_up() const
bool init(bool ignore_checks) override
Definition: mode_guided.cpp:39
bool enabled() const
bool is_zero(const T fVal1)
#define f(i)
ParametersG2 & g2
Definition: Copter.h:117
uint32_t millis()
YAW_BEHAVE_FACE_LEAD_VEHICLE
void run() override
Definition: mode_follow.cpp:38
float get_accel_z() const
bool get_target_heading(float &heading) const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
AC_P & get_pos_z_p()
float get_speed_down() const
YAW_BEHAVE_DIR_OF_FLIGHT
AC_PosControl *& pos_control
Definition: Copter.h:120
float length(void) const
const AC_P & get_pos_p() const
float length(void) const
float constrain_float(const float amt, const float low, const float high)
MOTOR_CLASS *& motors
Definition: Copter.h:124
bool is_zero(void) const
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
float & G_Dt
Definition: Copter.h:129
float sq(const T val)
float yaw_cd
Definition: mode_guided.cpp:23
bool init(bool ignore_checks) override
Definition: mode_follow.cpp:28
AP_Float & kP()