Sub: use configured rc input range for lights input instead of hard coded values

This commit is contained in:
Jacob Walser 2017-10-26 14:24:15 -04:00
parent 4e1c7fff37
commit fb2e87032d
2 changed files with 40 additions and 12 deletions

View File

@ -30,6 +30,9 @@ void Sub::init_joystick()
{ {
default_js_buttons(); default_js_buttons();
lights1 = RC_Channels::rc_channel(8)->get_radio_min();
lights2 = RC_Channels::rc_channel(9)->get_radio_min();
set_mode(MANUAL, MODE_REASON_TX_COMMAND); // Initialize flight mode set_mode(MANUAL, MODE_REASON_TX_COMMAND); // Initialize flight mode
if (g.numGainSettings < 1) { if (g.numGainSettings < 1) {
@ -195,47 +198,65 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
case JSButton::button_function_t::k_lights1_cycle: case JSButton::button_function_t::k_lights1_cycle:
if (!held) { if (!held) {
static bool increasing = true; static bool increasing = true;
RC_Channel* chan = RC_Channels::rc_channel(8);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
if (increasing) { if (increasing) {
lights1 = constrain_float(lights1+g.lights_step,1100,1900); lights1 = constrain_float(lights1+g.lights_step, min, max);
} else { } else {
lights1 = constrain_float(lights1-g.lights_step,1100,1900); lights1 = constrain_float(lights1-g.lights_step, min, max);
} }
if (lights1 >= 1900 || lights1 <= 1100) { if (lights1 >= max || lights1 <= min) {
increasing = !increasing; increasing = !increasing;
} }
} }
break; break;
case JSButton::button_function_t::k_lights1_brighter: case JSButton::button_function_t::k_lights1_brighter:
if (!held) { if (!held) {
lights1 = constrain_float(lights1+g.lights_step,1100,1900); 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);
} }
break; break;
case JSButton::button_function_t::k_lights1_dimmer: case JSButton::button_function_t::k_lights1_dimmer:
if (!held) { if (!held) {
lights1 = constrain_float(lights1-g.lights_step,1100,1900); 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);
} }
break; break;
case JSButton::button_function_t::k_lights2_cycle: case JSButton::button_function_t::k_lights2_cycle:
if (!held) { if (!held) {
static bool increasing = true; static bool increasing = true;
RC_Channel* chan = RC_Channels::rc_channel(9);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
if (increasing) { if (increasing) {
lights2 = constrain_float(lights2+g.lights_step,1100,1900); lights2 = constrain_float(lights2+g.lights_step, min, max);
} else { } else {
lights2 = constrain_float(lights2-g.lights_step,1100,1900); lights2 = constrain_float(lights2-g.lights_step, min, max);
} }
if (lights2 >= 1900 || lights2 <= 1100) { if (lights2 >= max || lights2 <= min) {
increasing = !increasing; increasing = !increasing;
} }
} }
break; break;
case JSButton::button_function_t::k_lights2_brighter: case JSButton::button_function_t::k_lights2_brighter:
if (!held) { if (!held) {
lights2 = constrain_float(lights2+g.lights_step,1100,1900); 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);
} }
break; break;
case JSButton::button_function_t::k_lights2_dimmer: case JSButton::button_function_t::k_lights2_dimmer:
if (!held) { if (!held) {
lights2 = constrain_float(lights2-g.lights_step,1100,1900); 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);
} }
break; break;
case JSButton::button_function_t::k_gain_toggle: case JSButton::button_function_t::k_gain_toggle:

View File

@ -32,8 +32,15 @@ void Sub::init_rc_in()
} }
hal.rcin->set_override(7, 1500); // camera tilt channel hal.rcin->set_override(7, 1500); // camera tilt channel
hal.rcin->set_override(8, 1100); // lights 1 channel
hal.rcin->set_override(9, 1100); // lights 2 channel RC_Channel* chan = RC_Channels::rc_channel(8);
uint16_t min = chan->get_radio_min();
hal.rcin->set_override(8, min); // lights 1 channel
chan = RC_Channels::rc_channel(9);
min = chan->get_radio_min();
hal.rcin->set_override(9, min); // lights 2 channel
hal.rcin->set_override(10, 1100); // video switch hal.rcin->set_override(10, 1100); // video switch
#endif #endif
} }