AR_AttitudeControl: move param defines from .h to .cpp

This commit is contained in:
Randy Mackay 2021-09-16 20:04:57 +09:00 committed by Andrew Tridgell
parent 7b0f059968
commit 9c54b3d252
2 changed files with 39 additions and 40 deletions

View File

@ -19,6 +19,45 @@
#include "AR_AttitudeControl.h" #include "AR_AttitudeControl.h"
#include <AP_GPS/AP_GPS.h> #include <AP_GPS/AP_GPS.h>
// attitude control default definition
#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
// throttle/speed control maximum acceleration/deceleration (in m/s) (_ACCEL_MAX parameter default)
#define AR_ATTCONTROL_THR_ACCEL_MAX 2.00f
// minimum speed in m/s
#define AR_ATTCONTROL_STEER_SPEED_MIN 1.0f
// speed (in m/s) at or below which vehicle is considered stopped (_STOP_SPEED parameter default)
#define AR_ATTCONTROL_STOP_SPEED_DEFAULT 0.1f
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {

View File

@ -4,46 +4,6 @@
#include <AC_PID/AC_PID.h> #include <AC_PID/AC_PID.h>
#include <AC_PID/AC_P.h> #include <AC_PID/AC_P.h>
// attitude control default definition
#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
// throttle/speed control maximum acceleration/deceleration (in m/s) (_ACCEL_MAX parameter default)
#define AR_ATTCONTROL_THR_ACCEL_MAX 2.00f
// minimum speed in m/s
#define AR_ATTCONTROL_STEER_SPEED_MIN 1.0f
// speed (in m/s) at or below which vehicle is considered stopped (_STOP_SPEED parameter default)
#define AR_ATTCONTROL_STOP_SPEED_DEFAULT 0.1f
class AR_AttitudeControl { class AR_AttitudeControl {
public: public: