Sub: JS_LIGHTS_STEP -> JS_LIGHTS_STEPS

This commit is contained in:
Jacob Walser 2017-10-26 15:42:56 -04:00
parent b7e367e21d
commit 1998cf93d2
3 changed files with 25 additions and 18 deletions

View File

@ -302,13 +302,13 @@ const AP_Param::Info Sub::var_info[] = {
// @Range: 1 10
GSCALAR(numGainSettings, "JS_GAIN_STEPS", 4),
// @Param: JS_LIGHTS_STEP
// @DisplayName: Lights step size
// @Description: Size of PWM increment in microseconds on lights servo
// @Param: JS_LIGHTS_STEPS
// @DisplayName: Lights brightness steps
// @Description: Number of steps in brightness between minimum and maximum brightness
// @User: Standard
// @Range: 30 400
// @Range: 1 10
// @Units: PWM
GSCALAR(lights_step, "JS_LIGHTS_STEP", 100),
GSCALAR(lights_steps, "JS_LIGHTS_STEPS", 8),
// @Param: JS_THR_GAIN
// @DisplayName: Throttle gain scalar

View File

@ -126,8 +126,8 @@ public:
k_param_maxGain,
k_param_minGain,
k_param_numGainSettings,
k_param_cam_tilt_step,
k_param_lights_step,
k_param_cam_tilt_step, // deprecated
k_param_lights_step, // deprecated
// Joystick button mapping parameters
k_param_jbtn_0 = 95,
@ -191,7 +191,7 @@ public:
k_param_terrain_follow = 182,
k_param_rc_feel_rp,
k_param_throttle_gain,
k_param_cam_tilt_center,
k_param_cam_tilt_center, // deprecated
k_param_frame_configuration,
// Acro Mode parameters
@ -208,7 +208,8 @@ public:
// RC_Mapper Library
k_param_rcmap, // Disabled
k_param_cam_slew_limit = 237,
k_param_cam_slew_limit = 237, // deprecated
k_param_lights_steps,
};
@ -273,7 +274,7 @@ public:
AP_Int8 numGainSettings;
AP_Float throttle_gain;
AP_Int16 lights_step;
AP_Int16 lights_steps;
// Joystick button parameters
JSButton jbtn_0;

View File

@ -201,10 +201,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
RC_Channel* chan = RC_Channels::rc_channel(8);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
uint16_t step = (max - min) / g.lights_steps;
if (increasing) {
lights1 = constrain_float(lights1+g.lights_step, min, max);
lights1 = constrain_float(lights1 + step, min, max);
} else {
lights1 = constrain_float(lights1-g.lights_step, min, max);
lights1 = constrain_float(lights1 - step, min, max);
}
if (lights1 >= max || lights1 <= min) {
increasing = !increasing;
@ -216,7 +217,8 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
RC_Channel* chan = RC_Channels::rc_channel(8);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
lights1 = constrain_float(lights1+g.lights_step, min, max);
uint16_t step = (max - min) / g.lights_steps;
lights1 = constrain_float(lights1 + step, min, max);
}
break;
case JSButton::button_function_t::k_lights1_dimmer:
@ -224,7 +226,8 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
RC_Channel* chan = RC_Channels::rc_channel(8);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
lights1 = constrain_float(lights1-g.lights_step, min, max);
uint16_t step = (max - min) / g.lights_steps;
lights1 = constrain_float(lights1 - step, min, max);
}
break;
case JSButton::button_function_t::k_lights2_cycle:
@ -233,10 +236,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
RC_Channel* chan = RC_Channels::rc_channel(9);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
uint16_t step = (max - min) / g.lights_steps;
if (increasing) {
lights2 = constrain_float(lights2+g.lights_step, min, max);
lights2 = constrain_float(lights2 + step, min, max);
} else {
lights2 = constrain_float(lights2-g.lights_step, min, max);
lights2 = constrain_float(lights2 - step, min, max);
}
if (lights2 >= max || lights2 <= min) {
increasing = !increasing;
@ -248,7 +252,8 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
RC_Channel* chan = RC_Channels::rc_channel(9);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
lights2 = constrain_float(lights2+g.lights_step, min, max);
uint16_t step = (max - min) / g.lights_steps;
lights2 = constrain_float(lights2 + step, min, max);
}
break;
case JSButton::button_function_t::k_lights2_dimmer:
@ -256,7 +261,8 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
RC_Channel* chan = RC_Channels::rc_channel(9);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
lights2 = constrain_float(lights2-g.lights_step, min, max);
uint16_t step = (max - min) / g.lights_steps;
lights2 = constrain_float(lights2 - step, min, max);
}
break;
case JSButton::button_function_t::k_gain_toggle: