mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Sub: Add cam tilt and lights step size parameters
This commit is contained in:
parent
5cc1d3293d
commit
0faf2a1f8e
@ -654,6 +654,22 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @Default: 4
|
||||
GSCALAR(numGainSettings, "JS_GAIN_STEPS", 4),
|
||||
|
||||
// @Param: JS_CAM_TILT_STEP
|
||||
// @DisplayName: Camera tilt step size
|
||||
// @Description: Size of PWM increment on camera tilt servo
|
||||
// @User: Standard
|
||||
// @Range: 30 400
|
||||
// @Default: 50
|
||||
GSCALAR(cam_tilt_step, "JS_CAM_TILT_STEP", 50),
|
||||
|
||||
// @Param: JS_LIGHTS_STEP
|
||||
// @DisplayName: Lights step size
|
||||
// @Description: Size of PWM increment on lights servo
|
||||
// @User: Standard
|
||||
// @Range: 30 400
|
||||
// @Default: 100
|
||||
GSCALAR(lights_step, "JS_LIGHTS_STEP", 100),
|
||||
|
||||
// @Group: BTN0_
|
||||
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
|
||||
GGROUP(jbtn_0, "BTN0_", JSButton),
|
||||
|
@ -405,7 +405,10 @@ public:
|
||||
|
||||
k_param_failsafe_terrain, // terrain failsafe behavior
|
||||
|
||||
k_param_xtrack_angle_limit // angle limit for xtrack correction in degrees
|
||||
k_param_xtrack_angle_limit, // angle limit for xtrack correction in degrees
|
||||
|
||||
k_param_cam_tilt_step,
|
||||
k_param_lights_step
|
||||
};
|
||||
|
||||
AP_Int16 format_version;
|
||||
@ -530,6 +533,9 @@ public:
|
||||
AP_Float minGain;
|
||||
AP_Int8 numGainSettings;
|
||||
|
||||
AP_Int16 cam_tilt_step;
|
||||
AP_Int16 lights_step;
|
||||
|
||||
// Joystick button parameters
|
||||
JSButton jbtn_0;
|
||||
JSButton jbtn_1;
|
||||
|
@ -132,10 +132,10 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held) {
|
||||
cam_tilt_goal = 1500;
|
||||
break;
|
||||
case JSButton::button_function_t::k_mount_tilt_up:
|
||||
cam_tilt_goal = constrain_float(cam_tilt_goal-30,800,2200);
|
||||
cam_tilt_goal = constrain_float(cam_tilt_goal-g.cam_tilt_step,800,2200);
|
||||
break;
|
||||
case JSButton::button_function_t::k_mount_tilt_down:
|
||||
cam_tilt_goal = constrain_float(cam_tilt_goal+30,800,2200);
|
||||
cam_tilt_goal = constrain_float(cam_tilt_goal+g.cam_tilt_step,800,2200);
|
||||
break;
|
||||
case JSButton::button_function_t::k_camera_trigger:
|
||||
break;
|
||||
@ -162,9 +162,9 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held) {
|
||||
if ( !held ) {
|
||||
static bool increasing = true;
|
||||
if ( increasing ) {
|
||||
lights1 = constrain_float(lights1+100,1100,1900);
|
||||
lights1 = constrain_float(lights1+g.lights_step,1100,1900);
|
||||
} else {
|
||||
lights1 = constrain_float(lights1-100,1100,1900);
|
||||
lights1 = constrain_float(lights1-g.lights_step,1100,1900);
|
||||
}
|
||||
if ( lights1 >= 1900 || lights1 <= 1100 ) {
|
||||
increasing = !increasing;
|
||||
@ -173,21 +173,21 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held) {
|
||||
break;
|
||||
case JSButton::button_function_t::k_lights1_brighter:
|
||||
if ( !held ) {
|
||||
lights1 = constrain_float(lights1+100,1100,1900);
|
||||
lights1 = constrain_float(lights1+g.lights_step,1100,1900);
|
||||
}
|
||||
break;
|
||||
case JSButton::button_function_t::k_lights1_dimmer:
|
||||
if ( !held ) {
|
||||
lights1 = constrain_float(lights1-100,1100,1900);
|
||||
lights1 = constrain_float(lights1-g.lights_step,1100,1900);
|
||||
}
|
||||
break;
|
||||
case JSButton::button_function_t::k_lights2_cycle:
|
||||
if ( !held ) {
|
||||
static bool increasing = true;
|
||||
if ( increasing ) {
|
||||
lights2 = constrain_float(lights2+100,1100,1900);
|
||||
lights2 = constrain_float(lights2+g.lights_step,1100,1900);
|
||||
} else {
|
||||
lights2 = constrain_float(lights2-100,1100,1900);
|
||||
lights2 = constrain_float(lights2-g.lights_step,1100,1900);
|
||||
}
|
||||
if ( lights2 >= 1900 || lights2 <= 1100 ) {
|
||||
increasing = !increasing;
|
||||
@ -196,12 +196,12 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held) {
|
||||
break;
|
||||
case JSButton::button_function_t::k_lights2_brighter:
|
||||
if ( !held ) {
|
||||
lights2 = constrain_float(lights2+100,1100,1900);
|
||||
lights2 = constrain_float(lights2+g.lights_step,1100,1900);
|
||||
}
|
||||
break;
|
||||
case JSButton::button_function_t::k_lights2_dimmer:
|
||||
if ( !held ) {
|
||||
lights2 = constrain_float(lights2-100,1100,1900);
|
||||
lights2 = constrain_float(lights2-g.lights_step,1100,1900);
|
||||
}
|
||||
break;
|
||||
case JSButton::button_function_t::k_gain_toggle:
|
||||
|
Loading…
Reference in New Issue
Block a user