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_Autorotation/AC_Autorotation.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_Motors/AP_Motors.h>
7
#include <AP_Motors/AP_MotorsHeli_RSC.h>
8
#include <Filter/Filter.h>
9
#include <Filter/LowPassFilter.h>
10
#include <AC_PID/AC_P.h>
11
12
13
class AC_Autorotation
14
{
15
public:
16
17
//Constructor
18
AC_Autorotation();
19
20
//--------Functions--------
21
void init_hs_controller(void); // Initialise head speed controller
22
void init_fwd_spd_controller(void); // Initialise forward speed controller
23
bool update_hs_glide_controller(float dt); // Update head speed controller
24
float get_rpm(void) const { return _current_rpm; } // Function just returns the rpm as last read in this library
25
float get_rpm(bool update_counter); // Function fetches fresh rpm update and continues sensor health monitoring
26
void set_target_head_speed(float ths) { _target_head_speed = ths; } // Sets the normalised target head speed
27
void set_col_cutoff_freq(float freq) { _col_cutoff_freq = freq; } // Sets the collective low pass filter cut off frequency
28
int16_t get_hs_set_point(void) { return _param_head_speed_set_point; }
29
float get_col_entry_freq(void) { return _param_col_entry_cutoff_freq; }
30
float get_col_glide_freq(void) { return _param_col_glide_cutoff_freq; }
31
float get_last_collective() const { return _collective_out; }
32
bool is_enable(void) { return _param_enable; }
33
void Log_Write_Autorotation(void) const;
34
void update_forward_speed_controller(void); // Update forward speed controller
35
void set_desired_fwd_speed(void) { _vel_target = _param_target_speed; } // Overloaded: Set desired speed for forward controller to parameter value
36
void set_desired_fwd_speed(float speed) { _vel_target = speed; } // Overloaded: Set desired speed to argument value
37
int32_t get_pitch(void) const { return _pitch_target; } // Get pitch target
38
float calc_speed_forward(void); // Calculates the forward speed in the horizontal plane
39
void set_dt(float delta_sec);
40
41
// User Settable Parameters
42
static const struct AP_Param::GroupInfo var_info[];
43
44
private:
45
46
//--------Internal Variables--------
47
float _current_rpm;
48
float _collective_out;
49
float _head_speed_error; // Error between target head speed and current head speed. Normalised by head speed set point RPM.
50
float _col_cutoff_freq; // Lowpass filter cutoff frequency (Hz) for collective.
51
uint8_t _unhealthy_rpm_counter; // Counter used to track RPM sensor unhealthy signal.
52
uint8_t _healthy_rpm_counter; // Counter used to track RPM sensor healthy signal.
53
float _target_head_speed; // Normalised target head speed. Normalised by head speed set point RPM.
54
float _p_term_hs; // Proportional contribution to collective setting.
55
float _ff_term_hs; // Following trim feed forward contribution to collective setting.
56
57
float _vel_target; // Forward velocity target.
58
float _pitch_target; // Pitch angle target.
59
float _accel_max; // Maximum acceleration limit.
60
int16_t _speed_forward_last; // The forward speed calculated in the previous cycle.
61
bool _flag_limit_accel; // Maximum acceleration limit reached flag.
62
float _accel_out_last; // Acceleration value used to calculate pitch target in previous cycle.
63
float _cmd_vel; // Command velocity, used to get PID values for acceleration calculation.
64
float _accel_target; // Acceleration target, calculated from PID.
65
float _delta_speed_fwd; // Change in forward speed between computation cycles.
66
float _dt; // Time step.
67
int16_t _speed_forward; // Measured forward speed.
68
float _vel_p; // Forward velocity P term.
69
float _vel_ff; // Forward velocity Feed Forward term.
70
float _accel_out; // Acceleration value used to calculate pitch target.
71
72
LowPassFilterFloat _accel_target_filter; // acceleration target filter
73
74
//--------Parameter Values--------
75
AP_Int8 _param_enable;
76
AC_P _p_hs;
77
AC_P _p_fw_vel;
78
AP_Int16 _param_head_speed_set_point;
79
AP_Int16 _param_target_speed;
80
AP_Float _param_col_entry_cutoff_freq;
81
AP_Float _param_col_glide_cutoff_freq;
82
AP_Int16 _param_accel_max;
83
AP_Int8 _param_rpm_instance;
84
AP_Float _param_fwd_k_ff;
85
86
//--------Internal Flags--------
87
struct controller_flags {
88
bool bad_rpm : 1;
89
bool bad_rpm_warning : 1;
90
} _flags;
91
92
//--------Internal Functions--------
93
void set_collective(float _collective_filter_cutoff) const;
94
95
// low pass filter for collective trim
96
LowPassFilterFloat col_trim_lpf;
97
};
98
99