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_AttitudeControl/AC_AttitudeControl_Heli.h
Views: 1798
1
#pragma once
2
3
/// @file AC_AttitudeControl_Heli.h
4
/// @brief ArduCopter attitude control library for traditional helicopters
5
6
#include "AC_AttitudeControl.h"
7
#include <AP_Motors/AP_MotorsHeli.h>
8
#include <AC_PID/AC_HELI_PID.h>
9
#include <Filter/Filter.h>
10
11
// default rate controller PID gains
12
#define AC_ATC_HELI_RATE_RP_P 0.024f
13
#define AC_ATC_HELI_RATE_RP_I 0.15f
14
#define AC_ATC_HELI_RATE_RP_D 0.001f
15
#define AC_ATC_HELI_RATE_RP_IMAX 0.4f
16
#define AC_ATC_HELI_RATE_RP_FF 0.15f
17
#define AC_ATC_HELI_RATE_RP_FILT_HZ 20.0f
18
#define AC_ATC_HELI_RATE_YAW_P 0.18f
19
#define AC_ATC_HELI_RATE_YAW_I 0.12f
20
#define AC_ATC_HELI_RATE_YAW_D 0.003f
21
#define AC_ATC_HELI_RATE_YAW_IMAX 0.4f
22
#define AC_ATC_HELI_RATE_YAW_FF 0.024f
23
#define AC_ATC_HELI_RATE_YAW_FILT_HZ 20.0f
24
25
#define AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX 0.95f // Heli's use 95% of max collective before limiting frame angle
26
#define AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE 0.02f
27
#define AC_ATTITUDE_HELI_RATE_RP_FF_FILTER 20.0f
28
#define AC_ATTITUDE_HELI_RATE_Y_FF_FILTER 20.0f
29
#define AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT 300
30
#define AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD ToRad(30.0f)
31
#define AC_ATTITUDE_HELI_INVERTED_TRANSITION_TIME 3.0f
32
33
class AC_AttitudeControl_Heli : public AC_AttitudeControl {
34
public:
35
AC_AttitudeControl_Heli( AP_AHRS_View &ahrs,
36
const AP_MultiCopter &aparm,
37
AP_MotorsHeli& motors);
38
39
// pid accessors
40
AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; }
41
AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; }
42
AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; }
43
const AC_PID& get_rate_roll_pid() const override { return _pid_rate_roll; }
44
const AC_PID& get_rate_pitch_pid() const override { return _pid_rate_pitch; }
45
const AC_PID& get_rate_yaw_pid() const override { return _pid_rate_yaw; }
46
47
// passthrough_bf_roll_pitch_rate_yaw - roll and pitch are passed through directly, body-frame rate target for yaw
48
void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds) override;
49
50
// subclass non-passthrough too, for external gyro, no flybar
51
void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) override;
52
53
// rate_controller_run - run lowest level body-frame rate controller and send outputs to the motors
54
// should be called at 100hz or more
55
virtual void rate_controller_run() override;
56
57
// Update Alt_Hold angle maximum
58
void update_althold_lean_angle_max(float throttle_in) override;
59
60
// use_leaky_i - controls whether we use leaky i term for body-frame to motor output stage
61
void use_leaky_i(bool leaky_i) override { _flags_heli.leaky_i = leaky_i; }
62
63
// use_flybar_passthrough - controls whether we pass-through
64
// control inputs to swash-plate and tail
65
void use_flybar_passthrough(bool passthrough, bool tail_passthrough) override {
66
_flags_heli.flybar_passthrough = passthrough;
67
_flags_heli.tail_passthrough = tail_passthrough;
68
}
69
70
// set_hover_roll_scalar - scales Hover Roll Trim parameter. To be used by vehicle code according to vehicle condition.
71
void set_hover_roll_trim_scalar(float scalar) override {_hover_roll_trim_scalar = constrain_float(scalar, 0.0f, 1.0f);}
72
73
// get_roll_trim - angle in centi-degrees to be added to roll angle for learn hover collective. Used by helicopter to counter tail rotor thrust in hover
74
float get_roll_trim_cd() override;
75
76
// Set output throttle
77
void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override;
78
79
// calculate total body frame throttle required to produce the given earth frame throttle
80
float get_throttle_boosted(float throttle_in);
81
82
// Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
83
void input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds) override;
84
85
// Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
86
void input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw) override;
87
88
// Command a thrust vector in the earth frame and a heading angle and/or rate
89
void input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw = true) override;
90
void input_thrust_vector_heading(const Vector3f& thrust_vector, float heading_angle_cd, float heading_rate_cds) override;
91
92
// enable/disable inverted flight
93
void set_inverted_flight(bool inverted) override { _inverted_flight = inverted; }
94
95
// accessor for inverted flight flag
96
bool get_inverted_flight() override { return _inverted_flight; }
97
98
// set the PID notch sample rates
99
void set_notch_sample_rate(float sample_rate) override;
100
101
// user settable parameters
102
static const struct AP_Param::GroupInfo var_info[];
103
104
private:
105
106
// To-Do: move these limits flags into the heli motors class
107
struct AttControlHeliFlags {
108
uint8_t leaky_i : 1; // 1 if we should use leaky i term for body-frame rate to motor stage
109
uint8_t flybar_passthrough : 1; // 1 if we should pass through pilots roll & pitch input directly to swash-plate
110
uint8_t tail_passthrough : 1; // 1 if we should pass through pilots yaw input to tail
111
} _flags_heli;
112
113
// true in inverted flight mode
114
bool _inverted_flight;
115
116
// Integrate vehicle rate into _att_error_rot_vec_rad
117
void integrate_bf_rate_error_to_angle_errors();
118
119
//
120
// body-frame rate controller
121
//
122
// rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target body-frame rate (in radians/sec) for roll, pitch and yaw
123
// outputs are sent directly to motor class
124
void rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads);
125
float rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_yaw_rads);
126
127
//
128
// throttle methods
129
//
130
131
// pass through for roll and pitch
132
float _passthrough_roll;
133
float _passthrough_pitch;
134
135
// pass through for yaw if tail_passthrough is set
136
float _passthrough_yaw;
137
138
// get_roll_trim - angle in centi-degrees to be added to roll angle. Used by helicopter to counter tail rotor thrust in hover
139
float get_roll_trim_rad() override { return radians(get_roll_trim_cd() * 0.01); }
140
141
// internal variables
142
float _hover_roll_trim_scalar = 0; // scalar used to suppress Hover Roll Trim
143
144
145
// This represents an euler axis-angle rotation vector from the vehicles
146
// estimated attitude to the reference (setpoint) attitude used in the attitude
147
// controller, in radians in the vehicle body frame of reference.
148
Vector3f _att_error_rot_vec_rad;
149
150
// parameters
151
AP_Int8 _piro_comp_enabled; // Flybar present or not. Affects attitude controller used during ACRO flight mode
152
AP_Int16 _hover_roll_trim; // Angle in centi-degrees used to counter tail rotor thrust in hover
153
154
// Roll and Pitch rate PIDs share the same defaults:
155
const AC_PID::Defaults rp_defaults {
156
AC_PID::Defaults{
157
.p = AC_ATC_HELI_RATE_RP_P,
158
.i = AC_ATC_HELI_RATE_RP_I,
159
.d = AC_ATC_HELI_RATE_RP_D,
160
.ff = AC_ATC_HELI_RATE_RP_FF,
161
.imax = AC_ATC_HELI_RATE_RP_IMAX,
162
.filt_T_hz = AC_ATTITUDE_HELI_RATE_RP_FF_FILTER,
163
.filt_E_hz = AC_ATC_HELI_RATE_RP_FILT_HZ,
164
.filt_D_hz = 0.0,
165
.srmax = 0,
166
.srtau = 1.0
167
}
168
};
169
AC_HELI_PID _pid_rate_roll { rp_defaults };
170
AC_HELI_PID _pid_rate_pitch { rp_defaults };
171
172
AC_HELI_PID _pid_rate_yaw {
173
AC_PID::Defaults{
174
.p = AC_ATC_HELI_RATE_YAW_P,
175
.i = AC_ATC_HELI_RATE_YAW_I,
176
.d = AC_ATC_HELI_RATE_YAW_D,
177
.ff = AC_ATC_HELI_RATE_YAW_FF,
178
.imax = AC_ATC_HELI_RATE_YAW_IMAX,
179
.filt_T_hz = AC_ATTITUDE_HELI_RATE_Y_FF_FILTER,
180
.filt_E_hz = AC_ATC_HELI_RATE_YAW_FILT_HZ,
181
.filt_D_hz = 0.0,
182
.srmax = 0,
183
.srtau = 1.0
184
}
185
};
186
187
};
188
189