ardupilot/ArduCopter/tuning.cpp

216 lines
6.6 KiB
C++
Raw Normal View History

2015-04-16 01:27:06 -03:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Copter.h"
2015-04-16 01:27:06 -03:00
/*
* tuning.pde - function to update various parameters in flight using the ch6 tuning knob
* This should not be confused with the AutoTune feature which can bve found in control_autotune.pde
*/
// tuning - updates parameters based on the ch6 tuning knob's position
// should be called at 3.3hz
void Copter::tuning() {
2015-04-16 01:27:06 -03:00
// exit immediately if not using tuning function, or when radio failsafe is invoked, so tuning values are not set to zero
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
if ((g.radio_tuning <= 0) || failsafe.radio || failsafe.radio_counter != 0 || g.rc_6.get_radio_in() == 0) {
2015-04-16 01:27:06 -03:00
return;
}
// set tuning range and then get new value
g.rc_6.set_range_in(g.radio_tuning_low,g.radio_tuning_high);
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
float tuning_value = (float)g.rc_6.get_control_in() / 1000.0f;
// Tuning Value should never be outside the bounds of the specified low and high value
tuning_value = constrain_float(tuning_value, g.radio_tuning_low/1000.0f, g.radio_tuning_high/1000.0f);
2015-04-16 01:27:06 -03:00
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
Log_Write_Parameter_Tuning(g.radio_tuning, tuning_value, g.rc_6.get_control_in(), g.radio_tuning_low, g.radio_tuning_high);
2015-04-16 01:27:06 -03:00
switch(g.radio_tuning) {
// Roll, Pitch tuning
case TUNING_STABILIZE_ROLL_PITCH_KP:
attitude_control.get_angle_roll_p().kP(tuning_value);
attitude_control.get_angle_pitch_p().kP(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_ROLL_PITCH_KP:
attitude_control.get_rate_roll_pid().kP(tuning_value);
attitude_control.get_rate_pitch_pid().kP(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_ROLL_PITCH_KI:
attitude_control.get_rate_roll_pid().kI(tuning_value);
attitude_control.get_rate_pitch_pid().kI(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_ROLL_PITCH_KD:
attitude_control.get_rate_roll_pid().kD(tuning_value);
attitude_control.get_rate_pitch_pid().kD(tuning_value);
2015-04-16 01:27:06 -03:00
break;
// Yaw tuning
case TUNING_STABILIZE_YAW_KP:
attitude_control.get_angle_yaw_p().kP(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_YAW_RATE_KP:
attitude_control.get_rate_yaw_pid().kP(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_YAW_RATE_KD:
attitude_control.get_rate_yaw_pid().kD(tuning_value);
2015-04-16 01:27:06 -03:00
break;
// Altitude and throttle tuning
case TUNING_ALTITUDE_HOLD_KP:
2015-04-16 01:27:06 -03:00
g.p_alt_hold.kP(tuning_value);
break;
case TUNING_THROTTLE_RATE_KP:
2015-04-16 01:27:06 -03:00
g.p_vel_z.kP(tuning_value);
break;
case TUNING_ACCEL_Z_KP:
2015-04-16 01:27:06 -03:00
g.pid_accel_z.kP(tuning_value);
break;
case TUNING_ACCEL_Z_KI:
2015-04-16 01:27:06 -03:00
g.pid_accel_z.kI(tuning_value);
break;
case TUNING_ACCEL_Z_KD:
2015-04-16 01:27:06 -03:00
g.pid_accel_z.kD(tuning_value);
break;
// Loiter and navigation tuning
case TUNING_LOITER_POSITION_KP:
2015-04-16 01:27:06 -03:00
g.p_pos_xy.kP(tuning_value);
break;
case TUNING_VEL_XY_KP:
2015-04-16 01:27:06 -03:00
g.pi_vel_xy.kP(tuning_value);
break;
case TUNING_VEL_XY_KI:
2015-04-16 01:27:06 -03:00
g.pi_vel_xy.kI(tuning_value);
break;
case TUNING_WP_SPEED:
2015-04-16 01:27:06 -03:00
// set waypoint navigation horizontal speed to 0 ~ 1000 cm/s
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
wp_nav.set_speed_xy(g.rc_6.get_control_in());
2015-04-16 01:27:06 -03:00
break;
// Acro roll pitch gain
case TUNING_ACRO_RP_KP:
2015-04-16 01:27:06 -03:00
g.acro_rp_p = tuning_value;
break;
// Acro yaw gain
case TUNING_ACRO_YAW_KP:
2015-04-16 01:27:06 -03:00
g.acro_yaw_p = tuning_value;
break;
#if FRAME_CONFIG == HELI_FRAME
case TUNING_HELI_EXTERNAL_GYRO:
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
motors.ext_gyro_gain((float)g.rc_6.get_control_in() / 1000.0f);
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_PITCH_FF:
attitude_control.get_heli_rate_pitch_pid().ff(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_ROLL_FF:
attitude_control.get_heli_rate_roll_pid().ff(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_YAW_FF:
attitude_control.get_heli_rate_yaw_pid().ff(tuning_value);
2015-04-16 01:27:06 -03:00
break;
#endif
case TUNING_DECLINATION:
2015-04-16 01:27:06 -03:00
// set declination to +-20degrees
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
compass.set_declination(ToRad((2.0f * g.rc_6.get_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
2015-04-16 01:27:06 -03:00
break;
case TUNING_CIRCLE_RATE:
2015-07-22 09:42:02 -03:00
// set circle rate up to approximately 45 deg/sec in either direction
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
circle_nav.set_rate((float)g.rc_6.get_control_in()/25.0f-20.0f);
2015-04-16 01:27:06 -03:00
break;
2016-04-27 08:37:04 -03:00
case TUNING_RANGEFINDER_GAIN:
// set rangefinder gain
g.rangefinder_gain.set(tuning_value);
2015-04-16 01:27:06 -03:00
break;
#if 0
// disabled for now - we need accessor functions
case TUNING_EKF_VERTICAL_POS:
// Tune the EKF that is being used
2015-04-16 01:27:06 -03:00
// EKF's baro vs accel (higher rely on accels more, baro impact is reduced)
if (!ahrs.get_NavEKF2().enabled()) {
ahrs.get_NavEKF()._gpsVertPosNoise = tuning_value;
} else {
ahrs.get_NavEKF2()._gpsVertPosNoise = tuning_value;
}
2015-04-16 01:27:06 -03:00
break;
case TUNING_EKF_HORIZONTAL_POS:
2015-04-16 01:27:06 -03:00
// EKF's gps vs accel (higher rely on accels more, gps impact is reduced)
if (!ahrs.get_NavEKF2().enabled()) {
ahrs.get_NavEKF()._gpsHorizPosNoise = tuning_value;
} else {
ahrs.get_NavEKF2()._gpsHorizPosNoise = tuning_value;
}
2015-04-16 01:27:06 -03:00
break;
case TUNING_EKF_ACCEL_NOISE:
2015-04-16 01:27:06 -03:00
// EKF's accel noise (lower means trust accels more, gps & baro less)
if (!ahrs.get_NavEKF2().enabled()) {
ahrs.get_NavEKF()._accNoise = tuning_value;
} else {
ahrs.get_NavEKF2()._accNoise = tuning_value;
}
2015-04-16 01:27:06 -03:00
break;
#endif
case TUNING_RC_FEEL_RP:
2015-04-16 01:27:06 -03:00
// roll-pitch input smoothing
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
g.rc_feel_rp = g.rc_6.get_control_in() / 10;
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_PITCH_KP:
attitude_control.get_rate_pitch_pid().kP(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_PITCH_KI:
attitude_control.get_rate_pitch_pid().kI(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_PITCH_KD:
attitude_control.get_rate_pitch_pid().kD(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_ROLL_KP:
attitude_control.get_rate_roll_pid().kP(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_ROLL_KI:
attitude_control.get_rate_roll_pid().kI(tuning_value);
2015-04-16 01:27:06 -03:00
break;
case TUNING_RATE_ROLL_KD:
attitude_control.get_rate_roll_pid().kD(tuning_value);
2015-04-16 01:27:06 -03:00
break;
#if FRAME_CONFIG != HELI_FRAME
case TUNING_RATE_MOT_YAW_HEADROOM:
2015-04-16 01:27:06 -03:00
motors.set_yaw_headroom(tuning_value*1000);
break;
#endif
2015-04-16 01:27:06 -03:00
case TUNING_RATE_YAW_FILT:
attitude_control.get_rate_yaw_pid().filt_hz(tuning_value);
2015-04-16 01:27:06 -03:00
break;
}
}