ArduCopter: reverted channel 5~8 to be regular RC_Channel objects, restored rc_camera_roll and rc_camera_pitch RC_Channels and created new rc_camera_yaw RC_Channel to control the camera mount servos.

Defined camera_mount (MNT_) in Parameters.h and Parameters.pde so that it appears in global parameters list.
Removed unused camera_*_gain and camaera_*_continuous parameters.
This commit is contained in:
rmackay9 2012-07-15 16:36:05 +09:00
parent 793fb7f059
commit 29b6ec0b11
2 changed files with 35 additions and 45 deletions

View File

@ -122,9 +122,10 @@ public:
//
// Camera parameters
// Camera and mount parameters
//
k_param_camera,
k_param_camera = 165,
k_param_camera_mount,
//
// 170: Radio settings
@ -137,8 +138,8 @@ public:
k_param_rc_6,
k_param_rc_7,
k_param_rc_8,
k_param_rc_9,
k_param_rc_10,
k_param_rc_camera_pitch,
k_param_rc_camera_roll,
k_param_throttle_min,
k_param_throttle_max,
k_param_throttle_fs_enabled,
@ -149,11 +150,8 @@ public:
k_param_radio_tuning,
k_param_radio_tuning_high,
k_param_radio_tuning_low,
k_param_camera_pitch_gain,
k_param_camera_roll_gain,
k_param_rc_speed,
k_param_camera_pitch_continuous,
k_param_camera_roll_continuous,
k_param_rc_speed = 192,
k_param_rc_camera_yaw = 193,
//
// 200: flight modes
@ -296,18 +294,18 @@ public:
RC_Channel rc_2;
RC_Channel rc_3;
RC_Channel rc_4;
RC_Channel_aux rc_5;
RC_Channel_aux rc_6;
RC_Channel_aux rc_7;
RC_Channel_aux rc_8;
RC_Channel_aux rc_9;
RC_Channel_aux rc_10;
RC_Channel rc_5;
RC_Channel rc_6;
RC_Channel rc_7;
RC_Channel rc_8;
#if MOUNT == ENABLED
RC_Channel_aux rc_camera_roll;
RC_Channel_aux rc_camera_pitch;
RC_Channel_aux rc_camera_yaw;
#endif
AP_Int16 rc_speed; // speed of fast RC Channels in Hz
AP_Float camera_pitch_gain;
AP_Float camera_roll_gain;
AP_Int8 camera_pitch_continuous;
AP_Int8 camera_roll_continuous;
AP_Float stabilize_d;
AP_Float stabilize_d_schedule;
@ -402,10 +400,6 @@ public:
rc_speed(RC_FAST_SPEED),
camera_pitch_gain (CAM_PITCH_GAIN),
camera_roll_gain (CAM_ROLL_GAIN),
camera_pitch_continuous (CAM_PITCH_CONTINUOUS),
camera_roll_continuous (CAM_ROLL_CONTINUOUS),
stabilize_d (STABILIZE_D),
stabilize_d_schedule (STABILIZE_D_SCHEDULE),
acro_p (ACRO_P),

View File

@ -214,30 +214,24 @@ static const AP_Param::Info var_info[] PROGMEM = {
GGROUP(rc_2, "RC2_", RC_Channel),
GGROUP(rc_3, "RC3_", RC_Channel),
GGROUP(rc_4, "RC4_", RC_Channel),
GGROUP(rc_5, "RC5_", RC_Channel),
GGROUP(rc_6, "RC6_", RC_Channel),
GGROUP(rc_7, "RC7_", RC_Channel),
GGROUP(rc_8, "RC8_", RC_Channel),
// @Group: RC5_
#if MOUNT == ENABLED
// @Group: CAM_R_
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_5, "RC5_", RC_Channel_aux),
GGROUP(rc_camera_roll, "CAM_R_", RC_Channel_aux),
// @Group: RC6_
// @Group: CAM_P_
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_6, "RC6_", RC_Channel_aux),
GGROUP(rc_camera_pitch, "CAM_P_", RC_Channel_aux),
// @Group: RC7_
// @Group: CAM_Y_
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_7, "RC7_", RC_Channel_aux),
// @Group: RC8_
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_8, "RC8_", RC_Channel_aux),
// @Group: RC9_
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_9, "RC9_", RC_Channel_aux),
// @Group: RC10_
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_10, "RC10_", RC_Channel_aux),
GGROUP(rc_camera_yaw, "CAM_Y_", RC_Channel_aux),
#endif
// @Param: RC_SPEED
// @DisplayName: ESC Update Speed
@ -249,10 +243,6 @@ static const AP_Param::Info var_info[] PROGMEM = {
// variable
//---------
GSCALAR(camera_pitch_gain, "CAM_P_G"),
GSCALAR(camera_roll_gain, "CAM_R_G"),
GSCALAR(camera_pitch_continuous,"CAM_P_CONT"),
GSCALAR(camera_roll_continuous, "CAM_R_CONT"),
GSCALAR(stabilize_d, "STAB_D"),
// @Param: STAB_D_S
@ -312,6 +302,12 @@ static const AP_Param::Info var_info[] PROGMEM = {
// @Path: ../libraries/AP_AHRS/AP_AHRS_DCM.cpp, ../libraries/AP_AHRS/AP_AHRS_Quaternion.cpp
GOBJECT(ahrs, "AHRS_", AP_AHRS),
#if MOUNT == ENABLED
// @Group: MNT_
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
GOBJECT(camera_mount, "MNT_", AP_Mount),
#endif
#ifdef DESKTOP_BUILD
GOBJECT(sitl, "SIM_", SITL),
#endif