Parameters: Added flag for camera pitch/roll servos (continuous or regular)
This commit is contained in:
parent
1b4bc490a0
commit
278e215a21
@ -141,6 +141,8 @@ public:
|
|||||||
k_param_camera_pitch_gain,
|
k_param_camera_pitch_gain,
|
||||||
k_param_camera_roll_gain,
|
k_param_camera_roll_gain,
|
||||||
k_param_rc_speed,
|
k_param_rc_speed,
|
||||||
|
k_param_camera_pitch_continuous,
|
||||||
|
k_param_camera_roll_continuous,
|
||||||
|
|
||||||
//
|
//
|
||||||
// 200: flight modes
|
// 200: flight modes
|
||||||
@ -286,6 +288,8 @@ public:
|
|||||||
|
|
||||||
AP_Float camera_pitch_gain;
|
AP_Float camera_pitch_gain;
|
||||||
AP_Float camera_roll_gain;
|
AP_Float camera_roll_gain;
|
||||||
|
AP_Int8 camera_pitch_continuous;
|
||||||
|
AP_Int8 camera_roll_continuous;
|
||||||
AP_Float stabilize_d;
|
AP_Float stabilize_d;
|
||||||
AP_Float stabilize_d_schedule;
|
AP_Float stabilize_d_schedule;
|
||||||
|
|
||||||
@ -382,6 +386,8 @@ public:
|
|||||||
|
|
||||||
camera_pitch_gain (CAM_PITCH_GAIN),
|
camera_pitch_gain (CAM_PITCH_GAIN),
|
||||||
camera_roll_gain (CAM_ROLL_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 (STABILIZE_D),
|
||||||
stabilize_d_schedule (STABILIZE_D_SCHEDULE),
|
stabilize_d_schedule (STABILIZE_D_SCHEDULE),
|
||||||
acro_p (ACRO_P),
|
acro_p (ACRO_P),
|
||||||
|
@ -166,9 +166,11 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
|
|
||||||
// variable
|
// variable
|
||||||
//---------
|
//---------
|
||||||
GSCALAR(camera_pitch_gain, "CAM_P_G"),
|
GSCALAR(camera_pitch_gain, "CAM_P_G"),
|
||||||
GSCALAR(camera_roll_gain, "CAM_R_G"),
|
GSCALAR(camera_roll_gain, "CAM_R_G"),
|
||||||
GSCALAR(stabilize_d, "STAB_D"),
|
GSCALAR(camera_pitch_continuous,"CAM_P_CONT"),
|
||||||
|
GSCALAR(camera_roll_continuous, "CAM_R_CONT"),
|
||||||
|
GSCALAR(stabilize_d, "STAB_D"),
|
||||||
|
|
||||||
// @Param: STAB_D_S
|
// @Param: STAB_D_S
|
||||||
// @DisplayName: Stabilize D Schedule
|
// @DisplayName: Stabilize D Schedule
|
||||||
|
@ -354,6 +354,15 @@
|
|||||||
# define CAM_PITCH_GAIN 1.0
|
# define CAM_PITCH_GAIN 1.0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// CAMERA SERVO TYPE
|
||||||
|
#ifndef CAM_PITCH_CONTINUOUS
|
||||||
|
# define CAM_PITCH_CONTINUOUS 0
|
||||||
|
#endif
|
||||||
|
#ifndef CAM_ROLL_CONTINUOUS
|
||||||
|
# define CAM_ROLL_CONTINUOUS 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// OPTICAL_FLOW
|
// OPTICAL_FLOW
|
||||||
|
Loading…
Reference in New Issue
Block a user