diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 9d8ef08d01..f2e6ccfe88 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -145,6 +145,7 @@ public: k_param_radio_tuning_low, k_param_camera_pitch_gain, k_param_camera_roll_gain, + k_param_rc_speed, // // 200: flight modes @@ -293,6 +294,7 @@ public: RC_Channel rc_8; RC_Channel rc_camera_pitch; RC_Channel rc_camera_roll; + AP_Int16 rc_speed; // speed of fast RC Channels in Hz AP_Float camera_pitch_gain; AP_Float camera_roll_gain; @@ -401,6 +403,8 @@ public: heli_collective_yaw_effect (0), #endif + rc_speed(RC_FAST_SPEED), + camera_pitch_gain (CAM_PITCH_GAIN), camera_roll_gain (CAM_ROLL_GAIN), stabilize_d (STABILIZE_D), diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index dbf0bd41fb..cfe4170285 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -105,6 +105,9 @@ static const AP_Param::Info var_info[] PROGMEM = { GGROUP(rc_camera_pitch, "CAM_P_", RC_Channel), GGROUP(rc_camera_roll, "CAM_R_", RC_Channel), + // speed of fast RC channels in Hz + GSCALAR(rc_speed, "RC_SPEED"), + // variable //--------- GSCALAR(camera_pitch_gain, "CAM_P_G"),