123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190 |
- #pragma once
- #include <AP_AHRS/AP_AHRS.h>
- #include <AP_Common/AP_Common.h>
- #include <AC_PID/AC_PID.h>
- #include <AC_PID/AC_P.h>
- #define AR_ATTCONTROL_STEER_ANG_P 2.50f
- #define AR_ATTCONTROL_STEER_RATE_FF 0.20f
- #define AR_ATTCONTROL_STEER_RATE_P 0.20f
- #define AR_ATTCONTROL_STEER_RATE_I 0.20f
- #define AR_ATTCONTROL_STEER_RATE_IMAX 1.00f
- #define AR_ATTCONTROL_STEER_RATE_D 0.00f
- #define AR_ATTCONTROL_STEER_RATE_FILT 10.00f
- #define AR_ATTCONTROL_STEER_RATE_MAX 360.0f
- #define AR_ATTCONTROL_STEER_ACCEL_MAX 180.0f
- #define AR_ATTCONTROL_THR_SPEED_P 0.20f
- #define AR_ATTCONTROL_THR_SPEED_I 0.20f
- #define AR_ATTCONTROL_THR_SPEED_IMAX 1.00f
- #define AR_ATTCONTROL_THR_SPEED_D 0.00f
- #define AR_ATTCONTROL_THR_SPEED_FILT 10.00f
- #define AR_ATTCONTROL_PITCH_THR_P 1.80f
- #define AR_ATTCONTROL_PITCH_THR_I 1.50f
- #define AR_ATTCONTROL_PITCH_THR_D 0.03f
- #define AR_ATTCONTROL_PITCH_THR_IMAX 1.0f
- #define AR_ATTCONTROL_PITCH_THR_FILT 10.0f
- #define AR_ATTCONTROL_BAL_SPEED_FF 1.0f
- #define AR_ATTCONTROL_DT 0.02f
- #define AR_ATTCONTROL_TIMEOUT_MS 200
- #define AR_ATTCONTROL_HEEL_SAIL_P 1.0f
- #define AR_ATTCONTROL_HEEL_SAIL_I 0.1f
- #define AR_ATTCONTROL_HEEL_SAIL_D 0.0f
- #define AR_ATTCONTROL_HEEL_SAIL_IMAX 1.0f
- #define AR_ATTCONTROL_HEEL_SAIL_FILT 10.0f
- #define AR_ATTCONTROL_DT 0.02f
- #define AR_ATTCONTROL_THR_ACCEL_MAX 2.00f
- #define AR_ATTCONTROL_STEER_SPEED_MIN 1.0f
- #define AR_ATTCONTROL_STOP_SPEED_DEFAULT 0.1f
- class AR_AttitudeControl {
- public:
-
- AR_AttitudeControl(AP_AHRS &ahrs);
-
-
-
-
-
-
- float get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt);
-
-
-
- float get_steering_out_heading(float heading_rad, float rate_max_rads, bool motor_limit_left, bool motor_limit_right, float dt);
-
-
- float get_turn_rate_from_heading(float heading_rad, float rate_max_rads) const;
-
-
-
- float get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt);
-
- float get_desired_turn_rate() const;
-
- float get_desired_lat_accel() const;
-
- bool get_lat_accel(float &lat_accel) const;
-
- float get_turn_rate_from_lat_accel(float lat_accel, float speed) const;
-
-
-
-
-
-
- void set_throttle_limits(float throttle_accel_max, float throttle_decel_max);
-
-
-
-
- float get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt);
-
- float get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt, bool &stopped);
-
-
-
- float get_throttle_out_from_pitch(float desired_pitch, float veh_speed_pct, bool motor_limit_low, bool motor_limit_high, float dt);
-
- float get_desired_pitch() const;
-
- float get_sail_out_from_heel(float desired_heel, float dt);
-
- AC_P& get_steering_angle_p() { return _steer_angle_p; }
- AC_PID& get_steering_rate_pid() { return _steer_rate_pid; }
- AC_PID& get_throttle_speed_pid() { return _throttle_speed_pid; }
- AC_PID& get_pitch_to_throttle_pid() { return _pitch_to_throttle_pid; }
- AC_PID& get_sailboat_heel_pid() { return _sailboat_heel_pid; }
-
- bool get_forward_speed(float &speed) const;
-
- float get_accel_max() const { return MAX(_throttle_accel_max, 0.0f); }
-
- float get_decel_max() const;
-
- bool speed_control_active() const;
-
- float get_desired_speed() const;
-
- float get_desired_speed_accel_limited(float desired_speed, float dt) const;
-
- float get_stopping_distance(float speed) const;
-
- void relax_I();
-
- static const struct AP_Param::GroupInfo var_info[];
- private:
-
- const AP_AHRS &_ahrs;
-
- AC_P _steer_angle_p;
- AC_PID _steer_rate_pid;
- AC_PID _throttle_speed_pid;
- AC_PID _pitch_to_throttle_pid;
- AP_Float _pitch_to_throttle_speed_ff;
- AP_Float _throttle_accel_max;
- AP_Float _throttle_decel_max;
- AP_Int8 _brake_enable;
- AP_Float _stop_speed;
- AP_Float _steer_accel_max;
- AP_Float _steer_rate_max;
-
- uint32_t _steer_lat_accel_last_ms;
- uint32_t _steer_turn_last_ms;
- float _desired_lat_accel;
- float _desired_turn_rate;
-
- uint32_t _speed_last_ms;
- float _desired_speed;
- uint32_t _stop_last_ms;
- bool _throttle_limit_low;
- bool _throttle_limit_high;
-
- uint32_t _balance_last_ms = 0;
-
- AC_PID _sailboat_heel_pid;
- uint32_t _heel_controller_last_ms = 0;
- };
|