123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_Param/AP_Param.h>
- #include <AP_Math/AP_Math.h>
- #include <AC_PID/AC_P.h> // P library
- #include <AC_PID/AC_PID.h> // PID library
- #include <AC_PID/AC_PI_2D.h> // PI library (2-axis)
- #include <AC_PID/AC_PID_2D.h> // PID library (2-axis)
- #include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library
- #include "AC_AttitudeControl.h"
- #include <AP_Motors/AP_Motors.h> // motors library
- #include <AP_Vehicle/AP_Vehicle.h> // common vehicle parameters
- #define POSCONTROL_ACCELERATION_MIN 50.0f
- #define POSCONTROL_ACCEL_XY 100.0f
- #define POSCONTROL_ACCEL_XY_MAX 980.0f
- #define POSCONTROL_STOPPING_DIST_UP_MAX 300.0f
- #define POSCONTROL_STOPPING_DIST_DOWN_MAX 200.0f
- #define POSCONTROL_SPEED 500.0f
- #define POSCONTROL_SPEED_DOWN -150.0f
- #define POSCONTROL_SPEED_UP 250.0f
- #define POSCONTROL_ACCEL_Z 250.0f
- #define POSCONTROL_LEASH_LENGTH_MIN 100.0f
- #define POSCONTROL_DT_50HZ 0.02f
- #define POSCONTROL_DT_400HZ 0.0025f
- #define POSCONTROL_ACTIVE_TIMEOUT_US 200000
- #define POSCONTROL_VEL_ERROR_CUTOFF_FREQ 4.0f
- #define POSCONTROL_THROTTLE_CUTOFF_FREQ 2.0f
- #define POSCONTROL_ACCEL_FILTER_HZ 2.0f
- #define POSCONTROL_JERK_RATIO 1.0f
- #define POSCONTROL_OVERSPEED_GAIN_Z 2.0f
- class AC_PosControl
- {
- public:
-
- AC_PosControl(const AP_AHRS_View& ahrs, const AP_InertialNav& inav,
- const AP_Motors& motors, AC_AttitudeControl& attitude_control);
-
-
-
- float run_z_controller_wangdan(float _vel);
-
-
- void set_dt(float delta_sec);
- float get_dt() const { return _dt; }
-
-
-
-
-
-
- void set_max_speed_z(float speed_down, float speed_up);
-
- float get_max_speed_up() const { return _speed_up_cms; }
-
- float get_max_speed_down() const { return _speed_down_cms; }
-
- float get_vel_target_z() const { return _vel_target.z; }
-
-
- void set_max_accel_z(float accel_cmss);
-
- float get_max_accel_z() const { return _accel_z_cms; }
-
-
- void calc_leash_length_z();
-
- void set_alt_target(float alt_cm) { _pos_target.z = alt_cm; }
-
-
-
-
- void set_alt_target_with_slew(float alt_cm, float dt);
-
-
-
-
-
- virtual void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend);
-
-
-
-
-
- virtual void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend);
-
-
-
- void add_takeoff_climb_rate(float climb_rate_cms, float dt);
-
- void set_alt_target_to_current_alt() { _pos_target.z = _inav.get_altitude(); }
-
- void shift_alt_target(float z_cm);
-
- void relax_alt_hold_controllers(float throttle_setting);
-
- float get_alt_target() const { return _pos_target.z; }
-
- float get_alt_error() const;
-
- float get_horizontal_error() const;
-
- void set_target_to_stopping_point_z();
-
- void get_stopping_point_z(Vector3f& stopping_point) const;
-
- void init_takeoff();
-
- bool is_active_z() const;
-
- void update_z_controller();
- float update_z_controller_f();
-
- float get_leash_down_z() const { return _leash_down_z; }
- float get_leash_up_z() const { return _leash_up_z; }
-
-
-
-
- float get_lean_angle_max_cd() const;
-
-
-
-
- void init_xy_controller();
-
-
- void set_max_accel_xy(float accel_cmss);
- float get_max_accel_xy() const { return _accel_cms; }
-
-
- void set_max_speed_xy(float speed_cms);
- float get_max_speed_xy() const { return _speed_cms; }
-
-
- void set_limit_accel_xy(void) { _limit.accel_xy = true; }
-
-
- void calc_leash_length_xy();
-
- void set_leash_length_xy(float leash) { _leash = leash; _flags.recalc_leash_xy = false; }
-
- const Vector3f& get_pos_target() const { return _pos_target; }
-
- void set_pos_target(const Vector3f& position);
-
- void set_xy_target(float x, float y);
-
- void shift_pos_xy_target(float x_cm, float y_cm);
-
- const Vector3f& get_desired_velocity() { return _vel_desired; }
-
- void set_desired_velocity_z(float vel_z_cms) {_vel_desired.z = vel_z_cms;}
-
- void clear_desired_velocity_ff_z() { _flags.use_desvel_ff_z = false; }
-
- void set_desired_accel_xy(float accel_lat_cms, float accel_lon_cms) { _accel_desired.x = accel_lat_cms; _accel_desired.y = accel_lon_cms; }
-
-
-
- void set_desired_velocity_xy(float vel_lat_cms, float vel_lon_cms) {_vel_desired.x = vel_lat_cms; _vel_desired.y = vel_lon_cms; }
-
-
- void set_desired_velocity(const Vector3f &des_vel) { _vel_desired = des_vel; }
-
- void override_vehicle_velocity_xy(const Vector2f& vel_xy) { _vehicle_horiz_vel = vel_xy; _flags.vehicle_horiz_vel_override = true; }
-
- void freeze_ff_z() { _flags.freeze_ff_z = true; }
-
- bool is_active_xy() const;
-
-
- void update_xy_controller();
-
- void set_target_to_stopping_point_xy();
-
-
-
-
-
- void get_stopping_point_xy(Vector3f &stopping_point) const;
-
- float get_distance_to_target() const;
-
- int32_t get_bearing_to_target() const;
-
-
- void init_vel_controller_xyz();
-
-
-
-
- void update_vel_controller_xy();
-
-
-
-
- void update_vel_controller_xyz();
-
- float get_roll() const { return _roll_target; }
- float get_pitch() const { return _pitch_target; }
-
- float get_leash_xy() const { return _leash; }
-
- AC_P& get_pos_z_p() { return _p_pos_z; }
- AC_P& get_vel_z_p() { return _p_vel_z; }
- AC_PID& get_accel_z_pid() { return _pid_accel_z; }
- AC_P& get_pos_xy_p() { return _p_pos_xy; }
- AC_PID_2D& get_vel_xy_pid() { return _pid_vel_xy; }
-
- const Vector3f& get_vel_target() const { return _vel_target; }
- const Vector3f& get_accel_target() const { return _accel_target; }
-
- void accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float& roll_target, float& pitch_target) const;
-
- void lean_angles_to_accel(float& accel_x_cmss, float& accel_y_cmss) const;
-
- float time_since_last_xy_update() const;
- void write_log();
-
- bool pre_arm_checks(const char *param_prefix,
- char *failure_msg,
- const uint8_t failure_msg_len);
- static const struct AP_Param::GroupInfo var_info[];
- AC_P _p_pos_z;
- float _dt;
- float _accel_z_cms;
- float last_alt;
- AC_PID _pid_accel_z;
- AC_P _p_vel_z;
- LowPassFilterFloat alt_rate;
- LowPassFilterFloat _vel_target_filter;
- LowPassFilterFloat current_alt;
- void calculate_rate(float dt);
- void calculate_target_rate(float dt);
- protected:
-
- struct poscontrol_flags {
- uint16_t recalc_leash_z : 1;
- uint16_t recalc_leash_xy : 1;
- uint16_t reset_desired_vel_to_pos : 1;
- uint16_t reset_accel_to_lean_xy : 1;
- uint16_t reset_rate_to_accel_z : 1;
- uint16_t freeze_ff_z : 1;
- uint16_t use_desvel_ff_z : 1;
- uint16_t vehicle_horiz_vel_override : 1;
- } _flags;
-
- struct poscontrol_limit_flags {
- uint8_t pos_up : 1;
- uint8_t pos_down : 1;
- uint8_t vel_up : 1;
- uint8_t vel_down : 1;
- uint8_t accel_xy : 1;
- } _limit;
-
-
-
-
-
-
-
-
- void run_z_controller();
- float run_z_controller_f();
-
-
-
-
-
- void desired_accel_to_vel(float nav_dt);
-
- void desired_vel_to_pos(float nav_dt);
-
-
-
-
-
- void run_xy_controller(float dt);
-
- float calc_leash_length(float speed_cms, float accel_cms, float kP) const;
-
- static bool limit_vector_length(float& vector_x, float& vector_y, float max_length);
-
- static Vector3f sqrt_controller(const Vector3f& error, float p, float second_ord_lim);
-
- void init_ekf_xy_reset();
- void check_for_ekf_xy_reset();
- void init_ekf_z_reset();
- void check_for_ekf_z_reset();
-
- const AP_AHRS_View & _ahrs;
- const AP_InertialNav& _inav;
- const AP_Motors& _motors;
- AC_AttitudeControl& _attitude_control;
-
- AP_Float _accel_xy_filt_hz;
- AP_Float _lean_angle_max;
-
-
-
- AC_P _p_pos_xy;
- AC_PID_2D _pid_vel_xy;
-
-
- uint64_t _last_update_xy_us;
- uint64_t _last_update_z_us;
- float _speed_down_cms;
- float _speed_up_cms;
- float _speed_cms;
-
- float _accel_last_z_cms;
- float _accel_cms;
- float _leash;
- float _leash_down_z;
- float _leash_up_z;
-
- float _roll_target;
- float _pitch_target;
-
- Vector3f _pos_target;
- Vector3f _pos_error;
- Vector3f _vel_desired;
- Vector3f _vel_target;
- Vector3f _vel_error;
- Vector3f _vel_last;
- Vector3f _accel_desired;
- Vector3f _accel_target;
- Vector3f _accel_error;
- Vector2f _vehicle_horiz_vel;
- LowPassFilterFloat _vel_error_filter;
- LowPassFilterVector2f _accel_target_filter;
-
- uint32_t _ekf_xy_reset_ms;
- uint32_t _ekf_z_reset_ms;
- };
|