APM:Copter
tuning.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  * Function to update various parameters in flight using the ch6 tuning knob
5  * This should not be confused with the AutoTune feature which can bve found in control_autotune.cpp
6  */
7 
8 // tuning - updates parameters based on the ch6 tuning knob's position
9 // should be called at 3.3hz
12 
13  // exit immediately if not using tuning function, or when radio failsafe is invoked, so tuning values are not set to zero
14  if ((g.radio_tuning <= 0) || failsafe.radio || failsafe.radio_counter != 0 || rc6->get_radio_in() == 0) {
15  return;
16  }
17 
18  uint16_t radio_in = rc6->get_radio_in();
19  float v = constrain_float((radio_in - rc6->get_radio_min()) / float(rc6->get_radio_max() - rc6->get_radio_min()), 0, 1);
20  int16_t control_in = g.radio_tuning_low + v * (g.radio_tuning_high - g.radio_tuning_low);
21  float tuning_value = control_in / 1000.0f;
22 
23  // Tuning Value should never be outside the bounds of the specified low and high value
24  tuning_value = constrain_float(tuning_value, g.radio_tuning_low/1000.0f, g.radio_tuning_high/1000.0f);
25 
27 
28  switch(g.radio_tuning) {
29 
30  // Roll, Pitch tuning
32  attitude_control->get_angle_roll_p().kP(tuning_value);
33  attitude_control->get_angle_pitch_p().kP(tuning_value);
34  break;
35 
37  attitude_control->get_rate_roll_pid().kP(tuning_value);
38  attitude_control->get_rate_pitch_pid().kP(tuning_value);
39  break;
40 
42  attitude_control->get_rate_roll_pid().kI(tuning_value);
43  attitude_control->get_rate_pitch_pid().kI(tuning_value);
44  break;
45 
47  attitude_control->get_rate_roll_pid().kD(tuning_value);
48  attitude_control->get_rate_pitch_pid().kD(tuning_value);
49  break;
50 
51  // Yaw tuning
53  attitude_control->get_angle_yaw_p().kP(tuning_value);
54  break;
55 
56  case TUNING_YAW_RATE_KP:
57  attitude_control->get_rate_yaw_pid().kP(tuning_value);
58  break;
59 
60  case TUNING_YAW_RATE_KD:
61  attitude_control->get_rate_yaw_pid().kD(tuning_value);
62  break;
63 
64  // Altitude and throttle tuning
66  pos_control->get_pos_z_p().kP(tuning_value);
67  break;
68 
70  pos_control->get_vel_z_p().kP(tuning_value);
71  break;
72 
73  case TUNING_ACCEL_Z_KP:
74  pos_control->get_accel_z_pid().kP(tuning_value);
75  break;
76 
77  case TUNING_ACCEL_Z_KI:
78  pos_control->get_accel_z_pid().kI(tuning_value);
79  break;
80 
81  case TUNING_ACCEL_Z_KD:
82  pos_control->get_accel_z_pid().kD(tuning_value);
83  break;
84 
85  // Loiter and navigation tuning
87  pos_control->get_pos_xy_p().kP(tuning_value);
88  break;
89 
90  case TUNING_VEL_XY_KP:
91  pos_control->get_vel_xy_pid().kP(tuning_value);
92  break;
93 
94  case TUNING_VEL_XY_KI:
95  pos_control->get_vel_xy_pid().kI(tuning_value);
96  break;
97 
98  case TUNING_WP_SPEED:
99  // set waypoint navigation horizontal speed to 0 ~ 1000 cm/s
100  wp_nav->set_speed_xy(control_in);
101  break;
102 
103  // Acro roll pitch gain
104  case TUNING_ACRO_RP_KP:
105  g.acro_rp_p = tuning_value;
106  break;
107 
108  // Acro yaw gain
109  case TUNING_ACRO_YAW_KP:
110  g.acro_yaw_p = tuning_value;
111  break;
112 
113 #if FRAME_CONFIG == HELI_FRAME
115  motors->ext_gyro_gain((float)control_in / 1000.0f);
116  break;
117 
119  attitude_control->get_rate_pitch_pid().ff(tuning_value);
120  break;
121 
122  case TUNING_RATE_ROLL_FF:
123  attitude_control->get_rate_roll_pid().ff(tuning_value);
124  break;
125 
126  case TUNING_RATE_YAW_FF:
127  attitude_control->get_rate_yaw_pid().ff(tuning_value);
128  break;
129 #endif
130 
131  case TUNING_DECLINATION:
132  // set declination to +-20degrees
133  compass.set_declination(ToRad((2.0f * control_in - g.radio_tuning_high)/100.0f), false); // 2nd parameter is false because we do not want to save to eeprom because this would have a performance impact
134  break;
135 
136 #if MODE_CIRCLE_ENABLED == ENABLED
137  case TUNING_CIRCLE_RATE:
138  // set circle rate up to approximately 45 deg/sec in either direction
139  circle_nav->set_rate((float)control_in/25.0f-20.0f);
140  break;
141 #endif
142 
143 #if RANGEFINDER_ENABLED == ENABLED
145  // set rangefinder gain
146  g.rangefinder_gain.set(tuning_value);
147  break;
148 #endif
149 
150 #if 0
151  // disabled for now - we need accessor functions
153  // Tune the EKF that is being used
154  // EKF's baro vs accel (higher rely on accels more, baro impact is reduced)
155  if (!ahrs.get_NavEKF2().enabled()) {
156  ahrs.get_NavEKF()._gpsVertPosNoise = tuning_value;
157  } else {
158  ahrs.get_NavEKF2()._gpsVertPosNoise = tuning_value;
159  }
160  break;
161 
163  // EKF's gps vs accel (higher rely on accels more, gps impact is reduced)
164  if (!ahrs.get_NavEKF2().enabled()) {
165  ahrs.get_NavEKF()._gpsHorizPosNoise = tuning_value;
166  } else {
167  ahrs.get_NavEKF2()._gpsHorizPosNoise = tuning_value;
168  }
169  break;
170 
172  // EKF's accel noise (lower means trust accels more, gps & baro less)
173  if (!ahrs.get_NavEKF2().enabled()) {
174  ahrs.get_NavEKF()._accNoise = tuning_value;
175  } else {
176  ahrs.get_NavEKF2()._accNoise = tuning_value;
177  }
178  break;
179 #endif
180 
181  case TUNING_RC_FEEL_RP:
182  // convert from control_in to input time constant
183  attitude_control->set_input_tc(1.0f / (2.0f + MAX((control_in * 0.01f), 0.0f)));
184  break;
185 
187  attitude_control->get_rate_pitch_pid().kP(tuning_value);
188  break;
189 
191  attitude_control->get_rate_pitch_pid().kI(tuning_value);
192  break;
193 
195  attitude_control->get_rate_pitch_pid().kD(tuning_value);
196  break;
197 
198  case TUNING_RATE_ROLL_KP:
199  attitude_control->get_rate_roll_pid().kP(tuning_value);
200  break;
201 
202  case TUNING_RATE_ROLL_KI:
203  attitude_control->get_rate_roll_pid().kI(tuning_value);
204  break;
205 
206  case TUNING_RATE_ROLL_KD:
207  attitude_control->get_rate_roll_pid().kD(tuning_value);
208  break;
209 
210 #if FRAME_CONFIG != HELI_FRAME
212  motors->set_yaw_headroom(tuning_value*1000);
213  break;
214 #endif
215 
217  attitude_control->get_rate_yaw_pid().filt_hz(tuning_value);
218  break;
219 
220 #if WINCH_ENABLED == ENABLED
221  case TUNING_WINCH: {
222  float desired_rate = 0.0f;
223  if (v > 0.6f) {
224  desired_rate = g2.winch.get_rate_max() * (v - 0.6f) / 0.4f;
225  }
226  if (v < 0.4f) {
227  desired_rate = g2.winch.get_rate_max() * (v - 0.4) / 0.4f;
228  }
229  g2.winch.set_desired_rate(desired_rate);
230  break;
231  }
232 #endif
233  }
234 }
void set_speed_xy(float speed_cms)
AP_Int8 radio_tuning
Definition: Parameters.h:440
AC_P & get_vel_z_p()
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
AC_AttitudeControl_t * attitude_control
Definition: Copter.h:492
AP_Float & kP()
int16_t get_radio_in() const
AC_Circle * circle_nav
Definition: Copter.h:497
static RC_Channel * rc_channel(uint8_t chan)
AC_P & get_pos_xy_p()
#define CH_6
#define ToRad(x)
AC_WPNav * wp_nav
Definition: Copter.h:494
bool enabled
MOTOR_CLASS * motors
Definition: Copter.h:422
AP_Float & kP()
AP_Float & kI()
AP_Int16 radio_tuning_low
Definition: Parameters.h:442
float get_rate_max() const
#define f(i)
AP_Float _gpsHorizPosNoise
AP_Winch winch
Definition: Parameters.h:576
AC_PID_2D & get_vel_xy_pid()
void tuning()
Definition: tuning.cpp:10
void set_rate(float deg_per_sec)
float v
AC_P & get_pos_z_p()
AP_Float _accNoise
void set_declination(float radians, bool save_to_eeprom=true)
Parameters g
Definition: Copter.h:208
float constrain_float(const float amt, const float low, const float high)
NavEKF2 & get_NavEKF2(void)
Compass compass
Definition: Copter.h:235
int16_t get_radio_min() const
int16_t get_radio_max() const
AP_Float rangefinder_gain
Definition: Parameters.h:395
struct Copter::@2 failsafe
AC_PosControl * pos_control
Definition: Copter.h:493
AP_Float & kD()
ParametersG2 g2
Definition: Copter.h:209
AP_Float acro_rp_p
Definition: Parameters.h:469
void set_desired_rate(float rate)
AC_PID & get_accel_z_pid()
AP_Float & kI()
AP_Float acro_yaw_p
Definition: Parameters.h:470
AP_Float & kP()
AP_Int16 radio_tuning_high
Definition: Parameters.h:441
void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high)
Definition: Log.cpp:349