Browse Source

lib/led: move drivers/lights/rgbled LED_RGB_MAXBRT -> SYS_RGB_MAXBRT

master
Daniel Agar 4 years ago
parent
commit
03bd5e0f48
  1. 54
      src/drivers/lights/rgbled/rgbled.cpp
  2. 39
      src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c.cpp
  3. 55
      src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c_params.c
  4. 31
      src/lib/led/led.cpp
  5. 31
      src/lib/led/led.h
  6. 21
      src/lib/led/led_params.c
  7. 13
      src/lib/parameters/param_translation.cpp

54
src/drivers/lights/rgbled/rgbled.cpp

@ -48,9 +48,6 @@ @@ -48,9 +48,6 @@
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/i2c_spi_buses.h>
#include <px4_platform_common/module.h>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/parameter_update.h>
using namespace time_literals;
@ -78,26 +75,20 @@ public: @@ -78,26 +75,20 @@ public:
void RunImpl();
protected:
void print_status() override;
private:
void print_status() override;
int send_led_enable(bool enable);
int send_led_rgb();
int get(bool &on, bool &powersave, uint8_t &r, uint8_t &g, uint8_t &b);
float _brightness{1.0f};
float _max_brightness{1.0f};
uint8_t _r{0};
uint8_t _g{0};
uint8_t _b{0};
bool _leds_enabled{true};
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
LedController _led_controller;
int send_led_enable(bool enable);
int send_led_rgb();
int get(bool &on, bool &powersave, uint8_t &r, uint8_t &g, uint8_t &b);
void update_params();
};
RGBLED::RGBLED(const I2CSPIDriverConfig &config) :
@ -119,8 +110,6 @@ RGBLED::init() @@ -119,8 +110,6 @@ RGBLED::init()
send_led_enable(false);
send_led_rgb();
update_params();
// kick off work queue
ScheduleNow();
@ -166,19 +155,6 @@ RGBLED::print_status() @@ -166,19 +155,6 @@ RGBLED::print_status()
void
RGBLED::RunImpl()
{
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// update parameters from storage
update_params();
// Immediately update to change brightness
send_led_rgb();
}
LedControlData led_control_data;
if (_led_controller.update(led_control_data) == 1) {
@ -267,9 +243,9 @@ RGBLED::send_led_rgb() @@ -267,9 +243,9 @@ RGBLED::send_led_rgb()
{
/* To scale from 0..255 -> 0..15 shift right by 4 bits */
const uint8_t msg[6] = {
SUB_ADDR_PWM0, static_cast<uint8_t>((_b >> 4) * _brightness * _max_brightness + 0.5f),
SUB_ADDR_PWM1, static_cast<uint8_t>((_g >> 4) * _brightness * _max_brightness + 0.5f),
SUB_ADDR_PWM2, static_cast<uint8_t>((_r >> 4) * _brightness * _max_brightness + 0.5f)
SUB_ADDR_PWM0, static_cast<uint8_t>((_b >> 4) * _brightness + 0.5f),
SUB_ADDR_PWM1, static_cast<uint8_t>((_g >> 4) * _brightness + 0.5f),
SUB_ADDR_PWM2, static_cast<uint8_t>((_r >> 4) * _brightness + 0.5f)
};
return transfer(msg, sizeof(msg), nullptr, 0);
}
@ -294,22 +270,6 @@ RGBLED::get(bool &on, bool &powersave, uint8_t &r, uint8_t &g, uint8_t &b) @@ -294,22 +270,6 @@ RGBLED::get(bool &on, bool &powersave, uint8_t &r, uint8_t &g, uint8_t &b)
return ret;
}
void
RGBLED::update_params()
{
int32_t maxbrt = 15;
param_get(param_find("LED_RGB_MAXBRT"), &maxbrt);
maxbrt = maxbrt > 15 ? 15 : maxbrt;
maxbrt = maxbrt < 0 ? 0 : maxbrt;
// A minimum of 2 "on" steps is required for breathe effect
if (maxbrt == 1) {
maxbrt = 2;
}
_max_brightness = maxbrt / 15.0f;
}
void
RGBLED::print_usage()
{

39
src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c.cpp

@ -44,12 +44,9 @@ @@ -44,12 +44,9 @@
#include <drivers/device/i2c.h>
#include <lib/led/led.h>
#include <lib/parameters/param.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/i2c_spi_buses.h>
#include <px4_platform_common/module.h>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/parameter_update.h>
using namespace time_literals;
@ -81,12 +78,10 @@ public: @@ -81,12 +78,10 @@ public:
private:
int send_led_rgb();
void update_params();
int write(uint8_t reg, uint8_t data);
float _brightness{1.0f};
float _max_brightness{1.0f};
uint8_t _r{0};
uint8_t _g{0};
@ -95,8 +90,6 @@ private: @@ -95,8 +90,6 @@ private:
volatile bool _should_run{true};
bool _leds_enabled{true};
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
LedController _led_controller;
uint8_t _red{NCP5623_LED_PWM0};
@ -154,8 +147,6 @@ RGBLED_NCP5623C::init() @@ -154,8 +147,6 @@ RGBLED_NCP5623C::init()
return ret;
}
update_params();
_running = true;
ScheduleNow();
@ -180,19 +171,6 @@ RGBLED_NCP5623C::probe() @@ -180,19 +171,6 @@ RGBLED_NCP5623C::probe()
void
RGBLED_NCP5623C::RunImpl()
{
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// update parameters from storage
update_params();
// Immediately update to change brightness
send_led_rgb();
}
LedControlData led_control_data;
if (_led_controller.update(led_control_data) == 1) {
@ -247,7 +225,7 @@ int @@ -247,7 +225,7 @@ int
RGBLED_NCP5623C::send_led_rgb()
{
uint8_t msg[7] = {0x20, 0x70, 0x40, 0x70, 0x60, 0x70, 0x80};
uint8_t brightness = 0x1f * _max_brightness;
uint8_t brightness = UINT8_MAX;
msg[0] = NCP5623_LED_CURRENT | (brightness & 0x1f);
msg[2] = _red | (uint8_t(_r * _brightness) & 0x1f);
@ -257,21 +235,6 @@ RGBLED_NCP5623C::send_led_rgb() @@ -257,21 +235,6 @@ RGBLED_NCP5623C::send_led_rgb()
return transfer(&msg[0], 7, nullptr, 0);
}
void
RGBLED_NCP5623C::update_params()
{
int32_t maxbrt = 31;
param_get(param_find("LED_RGB1_MAXBRT"), &maxbrt);
maxbrt = maxbrt > 31 ? 31 : maxbrt;
maxbrt = maxbrt < 0 ? 0 : maxbrt;
if (maxbrt == 0) {
maxbrt = 1;
}
_max_brightness = maxbrt / 31.0f;
}
void
RGBLED_NCP5623C::print_usage()
{

55
src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c_params.c

@ -1,55 +0,0 @@ @@ -1,55 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistribution of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistribution in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* @file rgbled_ncp5623c_params.c
*
* Parameters defined by the RBG led driver
*
* @author CUAVcaijie <caijie@cuav.net>
*/
#include <px4_platform_common/px4_config.h>
#include <parameters/param.h>
/**
* RGB Led brightness limit
*
* Set to 0 to disable, 1 for minimum brightness up to 31 (max)
*
* @min 0
* @max 31
* @group System
*/
PARAM_DEFINE_INT32(LED_RGB1_MAXBRT, 31);

31
src/lib/led/led.cpp

@ -40,6 +40,31 @@ @@ -40,6 +40,31 @@
int LedController::update(LedControlData &control_data)
{
bool had_changes = false; // did one of the outputs change?
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
updateParams();
const uint8_t max_brightness_prev = _max_brightness;
// set maximum brightness (0-255) from percentage
_max_brightness = roundf(math::constrain(_param_sys_rgb_maxbrt.get(), 0.f, 1.f) * UINT8_MAX);
// update existing
for (int i = 0; i < BOARD_MAX_LEDS; ++i) {
control_data.leds[i].brightness = math::min(_max_brightness, control_data.leds[i].brightness);
}
if (_max_brightness != max_brightness_prev) {
had_changes = true;
}
}
while (_led_control_sub.updated() || _force_update) {
const unsigned last_generation = _led_control_sub.get_last_generation();
@ -78,8 +103,6 @@ int LedController::update(LedControlData &control_data) @@ -78,8 +103,6 @@ int LedController::update(LedControlData &control_data)
_force_update = false;
}
bool had_changes = false; // did one of the outputs change?
// handle state updates
hrt_abstime now = hrt_absolute_time();
@ -207,7 +230,7 @@ void LedController::get_control_data(LedControlData &control_data) @@ -207,7 +230,7 @@ void LedController::get_control_data(LedControlData &control_data)
for (int i = 0; i < BOARD_MAX_LEDS; ++i) {
control_data.leds[i].color = led_control_s::COLOR_OFF; // set output to a defined state
control_data.leds[i].brightness = 255;
control_data.leds[i].brightness = _max_brightness;
for (int priority = led_control_s::MAX_PRIORITY; priority >= 0; --priority) {
bool flash_output_active = true;
@ -226,7 +249,7 @@ void LedController::get_control_data(LedControlData &control_data) @@ -226,7 +249,7 @@ void LedController::get_control_data(LedControlData &control_data)
// fade on and off
int counter = _states[i].current_blinking_time / (BREATHE_INTERVAL / 100);
int n = counter >= (BREATHE_STEPS / 2) ? BREATHE_STEPS - counter : counter;
control_data.leds[i].brightness = (n * n) * 255 / (BREATHE_STEPS * BREATHE_STEPS / 4); // (n/(steps/2))^2
control_data.leds[i].brightness = (n * n) * _max_brightness / (BREATHE_STEPS * BREATHE_STEPS / 4); // (n/(steps/2))^2
control_data.leds[i].color = cur_data.color;
_breathe_enabled = true;
break;

31
src/lib/led/led.h

@ -44,15 +44,23 @@ @@ -44,15 +44,23 @@
#include <drivers/drv_hrt.h>
#include <drivers/drv_led.h>
#include <px4_platform_common/module_params.h>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/led_control.h>
#include <uORB/topics/parameter_update.h>
#include <lib/parameters/param.h>
using namespace time_literals;
struct LedControlDataSingle {
uint8_t color; ///< one of led_control_s::COLOR_*
uint8_t brightness; ///< brightness in [0, 255]
uint8_t color{led_control_s::COLOR_OFF}; ///< one of led_control_s::COLOR_*
uint8_t brightness{0}; ///< brightness in [0, 255]
};
struct LedControlData {
LedControlDataSingle leds[BOARD_MAX_LEDS];
LedControlDataSingle leds[BOARD_MAX_LEDS] {};
};
@ -60,11 +68,11 @@ struct LedControlData { @@ -60,11 +68,11 @@ struct LedControlData {
** class LedController
* Handles the led_control topic: blinking, priorities and state updates.
*/
class LedController
class LedController : public ModuleParams
{
public:
LedController() = default;
~LedController() = default;
LedController() : ModuleParams(nullptr) {}
~LedController() override = default;
/**
* get maxium time between two consecutive calls to update() in us.
@ -148,8 +156,6 @@ private: @@ -148,8 +156,6 @@ private:
// handle infinite case
priority[next_priority].blink_times_left = 246;
}
}
void apply_next_state()
@ -175,7 +181,16 @@ private: @@ -175,7 +181,16 @@ private:
PerLedData _states[BOARD_MAX_LEDS]; ///< keep current LED states
uORB::Subscription _led_control_sub{ORB_ID(led_control)}; ///< uorb subscription
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
hrt_abstime _last_update_call{0};
uint8_t _max_brightness{UINT8_MAX};
bool _force_update{true}; ///< force an orb_copy in the beginning
bool _breathe_enabled{false}; ///< true if at least one of the led's is currently in breathe mode
DEFINE_PARAMETERS(
(ParamFloat<px4::params::SYS_RGB_MAXBRT>) _param_sys_rgb_maxbrt
)
};

21
src/drivers/lights/rgbled/rgbled_params.c → src/lib/led/led_params.c

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Copyright (c) 2015-2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -31,25 +31,12 @@ @@ -31,25 +31,12 @@
*
****************************************************************************/
/*
* @file rgbled_params.c
*
* Parameters defined by the RBG led driver
*
* @author Nate Weibley <nate.weibley@prioria.com>
*/
#include <px4_platform_common/px4_config.h>
#include <parameters/param.h>
/**
* RGB Led brightness limit
*
* Set to 0 to disable, 1 for minimum brightness up to 15 (max)
* Set to 0 to disable, 1 for maximum brightness
*
* @min 0
* @max 15
* @unit %
* @group System
*/
PARAM_DEFINE_INT32(LED_RGB_MAXBRT, 15);
PARAM_DEFINE_FLOAT(SYS_RGB_MAXBRT, 1.f);

13
src/lib/parameters/param_translation.cpp

@ -38,6 +38,7 @@ @@ -38,6 +38,7 @@
#include <lib/drivers/device/Device.hpp>
#include <drivers/drv_sensor.h>
#include <lib/parameters/param.h>
#include <lib/mathlib/mathlib.h>
bool param_modify_on_import(bson_node_t node)
{
@ -91,6 +92,18 @@ bool param_modify_on_import(bson_node_t node) @@ -91,6 +92,18 @@ bool param_modify_on_import(bson_node_t node)
}
}
// 2021-08-27: translate LED_RGB_MAXBRT (0-15) to SYS_RGB_MAXBRT(0.f-1.f)
if (node->type == BSON_INT32) {
if (strcmp("LED_RGB_MAXBRT", node->name) == 0) {
// convert integer (0-15) to float percentage
node->d = math::constrain(static_cast<double>(node->i) / 15., 0., 1.);
node->type = BSON_DOUBLE;
strcpy(node->name, "SYS_RGB_MAXBRT");
PX4_INFO("param migrating LED_RGB_MAXBRT (removed) -> SYS_RGB_MAXBRT: value=%.3f", node->d);
return true;
}
}
// 2020-06-29 (v1.11 beta): translate CAL_ACCx_EN/CAL_GYROx_EN/CAL_MAGx_EN -> CAL_ACCx_PRIO/CAL_GYROx_PRIO/CAL_MAGx_PRIO
if (node->type == BSON_INT32) {

Loading…
Cancel
Save