mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: added LED_BRIGHTNESS param
default was too bright
This commit is contained in:
parent
f4a1410434
commit
2857b57d92
|
@ -50,6 +50,10 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||
GOBJECT(baro, "BARO_", AP_Baro),
|
||||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_NEOPIXEL_COUNT
|
||||
GSCALAR(led_brightness, "LED_BRIGHTNESS", 50),
|
||||
#endif
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
||||
|
|
|
@ -18,6 +18,7 @@ public:
|
|||
k_param_can_baudrate,
|
||||
k_param_baro,
|
||||
k_param_buzz_volume,
|
||||
k_param_led_brightness,
|
||||
};
|
||||
|
||||
AP_Int16 format_version;
|
||||
|
@ -26,6 +27,9 @@ public:
|
|||
#ifdef HAL_PERIPH_ENABLE_BUZZER
|
||||
AP_Int8 buzz_volume;
|
||||
#endif
|
||||
#ifdef HAL_PERIPH_NEOPIXEL_COUNT
|
||||
AP_Int8 led_brightness;
|
||||
#endif
|
||||
|
||||
Parameters() {}
|
||||
};
|
||||
|
|
|
@ -422,9 +422,15 @@ static void handle_lightscommand(CanardInstance* ins, CanardRxTransfer* transfer
|
|||
uavcan_equipment_indication_SingleLightCommand &cmd = req.commands.data[i];
|
||||
// to get the right color proportions we scale the green so that is uses the
|
||||
// same number of bits as red and blue
|
||||
const uint8_t red = cmd.color.red<<3;
|
||||
const uint8_t green = (cmd.color.green>>1)<<3;
|
||||
const uint8_t blue = cmd.color.blue<<3;
|
||||
uint8_t red = cmd.color.red<<3;
|
||||
uint8_t green = (cmd.color.green>>1)<<3;
|
||||
uint8_t blue = cmd.color.blue<<3;
|
||||
if (periph.g.led_brightness != 100 && periph.g.led_brightness >= 0) {
|
||||
float scale = periph.g.led_brightness * 0.01;
|
||||
red = constrain_int16(red * scale, 0, 255);
|
||||
green = constrain_int16(green * scale, 0, 255);
|
||||
blue = constrain_int16(blue * scale, 0, 255);
|
||||
}
|
||||
hal.rcout->set_neopixel_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN, (1U<<HAL_PERIPH_NEOPIXEL_COUNT)-1,
|
||||
red, green, blue);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue