CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_WPNav/AC_Loiter.h
Views: 1798
1
#pragma once
2
3
#include <AP_Common/AP_Common.h>
4
#include <AP_Param/AP_Param.h>
5
#include <AP_Math/AP_Math.h>
6
#include <AP_Common/Location.h>
7
#include <AP_InertialNav/AP_InertialNav.h>
8
#include <AC_AttitudeControl/AC_PosControl.h>
9
#include <AC_AttitudeControl/AC_AttitudeControl.h>
10
#include <AC_Avoidance/AC_Avoid.h>
11
12
class AC_Loiter
13
{
14
public:
15
16
/// Constructor
17
AC_Loiter(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control);
18
19
/// init_target to a position in cm from ekf origin
20
void init_target(const Vector2f& position);
21
22
/// initialize's position and feed-forward velocity from current pos and velocity
23
void init_target();
24
25
/// reduce response for landing
26
void soften_for_landing();
27
28
/// set pilot desired acceleration in centi-degrees
29
// dt should be the time (in seconds) since the last call to this function
30
void set_pilot_desired_acceleration(float euler_roll_angle_cd, float euler_pitch_angle_cd);
31
32
/// gets pilot desired acceleration, body frame, [forward,right]
33
Vector2f get_pilot_desired_acceleration() const { return Vector2f{_desired_accel.x, _desired_accel.y}; }
34
35
/// clear pilot desired acceleration
36
void clear_pilot_desired_acceleration() {
37
set_pilot_desired_acceleration(0, 0);
38
}
39
40
/// get vector to stopping point based on a horizontal position and velocity
41
void get_stopping_point_xy(Vector2f& stopping_point) const;
42
43
/// get horizontal distance to loiter target in cm
44
float get_distance_to_target() const { return _pos_control.get_pos_error_xy_cm(); }
45
46
/// get bearing to target in centi-degrees
47
int32_t get_bearing_to_target() const { return _pos_control.get_bearing_to_target_cd(); }
48
49
/// get maximum lean angle when using loiter
50
float get_angle_max_cd() const;
51
52
/// run the loiter controller
53
void update(bool avoidance_on = true);
54
55
/// get desired roll, pitch which should be fed into stabilize controllers
56
float get_roll() const { return _pos_control.get_roll_cd(); }
57
float get_pitch() const { return _pos_control.get_pitch_cd(); }
58
Vector3f get_thrust_vector() const { return _pos_control.get_thrust_vector(); }
59
60
static const struct AP_Param::GroupInfo var_info[];
61
62
protected:
63
64
// sanity check parameters
65
void sanity_check_params();
66
67
/// updates desired velocity (i.e. feed forward) with pilot requested acceleration and fake wind resistance
68
/// updated velocity sent directly to position controller
69
void calc_desired_velocity(bool avoidance_on = true);
70
71
// references and pointers to external libraries
72
const AP_InertialNav& _inav;
73
const AP_AHRS_View& _ahrs;
74
AC_PosControl& _pos_control;
75
const AC_AttitudeControl& _attitude_control;
76
77
// parameters
78
AP_Float _angle_max; // maximum pilot commanded angle in degrees. Set to zero for 2/3 Angle Max
79
AP_Float _speed_cms; // maximum horizontal speed in cm/s while in loiter
80
AP_Float _accel_cmss; // loiter's max acceleration in cm/s/s
81
AP_Float _brake_accel_cmss; // loiter's acceleration during braking in cm/s/s
82
AP_Float _brake_jerk_max_cmsss;
83
AP_Float _brake_delay; // delay (in seconds) before loiter braking begins after sticks are released
84
85
// loiter controller internal variables
86
Vector2f _desired_accel; // slewed pilot's desired acceleration in lat/lon frame
87
Vector2f _predicted_accel;
88
Vector2f _predicted_euler_angle;
89
Vector2f _predicted_euler_rate;
90
uint32_t _brake_timer; // system time that brake was initiated
91
float _brake_accel; // acceleration due to braking from previous iteration (used for jerk limiting)
92
};
93
94