Path: blob/master/libraries/AC_Autorotation/AC_Autorotation.h
9649 views
#pragma once12#include <AP_Common/AP_Common.h>3#include <AP_Param/AP_Param.h>4#include <AP_Math/AP_Math.h>5#include <AP_Motors/AP_Motors.h>6#include <AP_Motors/AP_MotorsHeli_RSC.h>7#include <Filter/LowPassFilter.h>8#include <AC_PID/AC_P.h>9#include <AC_PID/AC_PID_Basic.h>10#include <AC_AttitudeControl/AC_AttitudeControl.h>1112class AC_Autorotation13{14public:1516//Constructor17AC_Autorotation(AP_MotorsHeli*& motors, AC_AttitudeControl*& att_crtl);1819void init(void);2021bool enabled(void) const { return _param_enable.get() > 0; }2223// Init and run entry phase controller24void init_entry(void);25void run_entry(float pilot_norm_accel);2627// Init and run the glide phase controller28void init_glide(void);29void run_glide(float pilot_norm_accel);3031// Run the landed phase controller to zero the desired vels and accels32void run_landed(void);3334// Arming checks for autorotation, mostly checking for miss-configurations35bool arming_checks(size_t buflen, char *buffer) const;3637// Logging of lower rate autorotation specific variables38void log_write_autorotation(void) const;3940// Returns true if we have met the autorotation-specific reasons to think we have landed41bool check_landed(void);4243// Dynamically update time step used in autorotation controllers44void set_dt(float delta_sec);4546// Helper to get measured head speed that has been normalised by head speed set point47bool get_norm_head_speed(float& norm_rpm) const;4849// User Settable Parameters50static const struct AP_Param::GroupInfo var_info[];5152static const uint32_t entry_time_ms = 2000; // (ms) Number of milliseconds that the entry phase operates for5354private:5556// References to other libraries57AP_MotorsHeli*& _motors_heli;58AC_AttitudeControl*& _attitude_control;5960// Calculates the forward ground speed in the horizontal plane61float get_speed_forward_ms(void) const;6263// (s) Time step, updated dynamically from vehicle64float _dt;6566// Parameter values67AP_Int8 _param_enable;68AC_P _p_hs{1.0};69AP_Float _param_head_speed_set_point;70AP_Float _param_target_speed_ms;71AP_Float _param_col_entry_cutoff_freq;72AP_Float _param_col_glide_cutoff_freq;73AP_Float _param_accel_max_mss;74AP_Int8 _param_rpm_instance;75AP_Float _param_fwd_k_ff;7677// Forward speed controller78void update_forward_speed_controller(float pilot_norm_accel);79AC_PID_Basic _fwd_speed_pid{2.0, 2.0, 0.2, 0.1, 4.0, 0.0, 10.0}; // PID object for vel to accel controller, Default values for kp, ki, kd, kff, imax, filt E Hz, filt D Hz80bool _limit_accel; // flag used for limiting integrator wind up if vehicle is against an accel or angle limit81float _desired_vel_ms; // (m/s) This is the velocity that we want. This is the variable that is set by the invoking function to request a certain speed82float _target_vel_ms; // (m/s) This is the acceleration constrained velocity that we are allowed8384// Head speed controller variables85void update_headspeed_controller(void); // Update controller used to drive head speed with collective86float _hs_accel; // The head speed target acceleration during the entry phase87float _head_speed_error; // Error between target head speed and current head speed. Normalised by head speed set point RPM.88float _target_head_speed; // Normalised target head speed. Normalised by head speed set point RPM.89float _p_term_hs; // Proportional contribution to collective setting.90float _ff_term_hs; // Following trim feed forward contribution to collective setting.91LowPassFilterFloat col_trim_lpf; // Low pass filter for collective trim9293// Flags used to check if we believe the aircraft has landed94struct {95bool min_speed;96bool land_col;97bool is_still;98} _landed_reason;99100// Parameter accessors that provide value constraints101float get_accel_max_mss(void) const { return MAX(_param_accel_max_mss.get(), 0.5); }102};103104105