Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Rover/mode_follow.cpp
9390 views
1
#include "Rover.h"
2
3
#if MODE_FOLLOW_ENABLED
4
// initialize follow mode
5
bool ModeFollow::_enter()
6
{
7
if (!g2.follow.enabled()) {
8
return false;
9
}
10
11
// initialise speed to waypoint speed
12
_desired_speed = g2.wp_nav.get_default_speed();
13
14
return true;
15
}
16
17
// exit handling
18
void ModeFollow::_exit()
19
{
20
g2.follow.clear_offsets_if_required();
21
}
22
23
void ModeFollow::update()
24
{
25
// stop vehicle if no speed estimate
26
float speed;
27
if (!attitude_control.get_forward_speed(speed)) {
28
// no valid speed so stop
29
g2.motors.set_throttle(0.0f);
30
g2.motors.set_steering(0.0f);
31
return;
32
}
33
34
Vector3f dist_vec; // vector to lead vehicle
35
Vector3f dist_vec_offs; // vector to lead vehicle + offset
36
Vector3f vel_of_target; // velocity of lead vehicle
37
38
// if no target simply stop the vehicle
39
if (!g2.follow.get_target_dist_and_vel_NED_m(dist_vec, dist_vec_offs, vel_of_target)) {
40
_reached_destination = true;
41
stop_vehicle();
42
return;
43
}
44
45
// calculate desired velocity vector
46
Vector2f desired_velocity_ne;
47
const float kp = g2.follow.get_pos_p().kP();
48
desired_velocity_ne.x = vel_of_target.x + (dist_vec_offs.x * kp);
49
desired_velocity_ne.y = vel_of_target.y + (dist_vec_offs.y * kp);
50
51
// if the desired velocity is less than 3cm/sec, stop vehicle
52
if (desired_velocity_ne.length() < 0.03f) {
53
_reached_destination = true;
54
stop_vehicle();
55
return;
56
}
57
58
//if the target vehicle velocity is less than 3cm/sec and the distance to the target vehicle is less than the turn radius, stop vehicle
59
if (vel_of_target.length() < 0.03f && dist_vec_offs.length() < g2.turn_radius) {
60
_reached_destination = true;
61
stop_vehicle();
62
return;
63
}
64
65
// we have not reached the target
66
_reached_destination = false;
67
68
// scale desired velocity to stay within horizontal speed limit
69
float desired_speed = safe_sqrt(sq(desired_velocity_ne.x) + sq(desired_velocity_ne.y));
70
if (!is_zero(desired_speed) && (desired_speed > _desired_speed)) {
71
const float scalar_xy = _desired_speed / desired_speed;
72
desired_velocity_ne *= scalar_xy;
73
desired_speed = _desired_speed;
74
}
75
76
// calculate vehicle heading
77
const float desired_yaw_cd = wrap_180_cd(rad_to_cd(atan2f(desired_velocity_ne.y, desired_velocity_ne.x)));
78
79
// run steering and throttle controllers
80
calc_steering_to_heading(desired_yaw_cd);
81
calc_throttle(desired_speed, true);
82
}
83
84
// return desired heading (in degrees) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)
85
float ModeFollow::wp_bearing() const
86
{
87
return g2.follow.get_bearing_to_target_deg();
88
}
89
90
// return distance (in meters) to destination
91
float ModeFollow::get_distance_to_destination() const
92
{
93
return g2.follow.get_distance_to_target_m();
94
}
95
96
// set desired speed in m/s
97
bool ModeFollow::set_desired_speed(float speed)
98
{
99
if (is_negative(speed)) {
100
return false;
101
}
102
_desired_speed = speed;
103
return true;
104
}
105
106
#endif // MODE_FOLLOW_ENABLED
107
108