forked from Archive/PX4-Autopilot
lights: use driver base class
This commit is contained in:
parent
692d262e0e
commit
ec2de33547
|
@ -68,13 +68,13 @@ unset BOARD_RC_DEFAULTS
|
|||
#
|
||||
# Start system state indicator.
|
||||
#
|
||||
rgbled start
|
||||
rgbled_ncp5623c start
|
||||
rgbled start -X
|
||||
rgbled_ncp5623c start -X
|
||||
rgbled_pwm start
|
||||
|
||||
if param greater LIGHT_EN_BLINKM 0
|
||||
then
|
||||
if blinkm start
|
||||
if blinkm start -X
|
||||
then
|
||||
blinkm systemstate
|
||||
fi
|
||||
|
|
|
@ -198,13 +198,13 @@ else
|
|||
#
|
||||
# Start system state indicator.
|
||||
#
|
||||
rgbled start
|
||||
rgbled_ncp5623c start
|
||||
rgbled start -X
|
||||
rgbled_ncp5623c start -X
|
||||
rgbled_pwm start
|
||||
|
||||
if param greater LIGHT_EN_BLINKM 0
|
||||
then
|
||||
if blinkm start
|
||||
if blinkm start -X
|
||||
then
|
||||
blinkm systemstate
|
||||
fi
|
||||
|
|
|
@ -9,7 +9,7 @@ set BOARD_RC /etc/init.d/rc.board
|
|||
|
||||
uorb start
|
||||
|
||||
if rgbled start
|
||||
if rgbled start -X
|
||||
then
|
||||
led_control on -c blue
|
||||
fi
|
||||
|
|
|
@ -3,6 +3,8 @@
|
|||
# PX4 FMUv2 specific board sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
rgbled start -I
|
||||
|
||||
adc start
|
||||
|
||||
# External I2C bus
|
||||
|
|
|
@ -3,6 +3,8 @@
|
|||
# PX4 FMUv3 specific board sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
rgbled start -I
|
||||
|
||||
adc start
|
||||
|
||||
# External I2C bus
|
||||
|
|
|
@ -3,6 +3,8 @@
|
|||
# PX4 FMUv4pro specific board sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
rgbled start -I
|
||||
|
||||
adc start
|
||||
|
||||
# Internal SPI bus ICM-20608-G
|
||||
|
|
|
@ -15,7 +15,7 @@ fi
|
|||
if param compare SYS_AUTOSTART 6002
|
||||
then
|
||||
# GPS LED
|
||||
rgbled_ncp5623c start -a 0x38
|
||||
rgbled_ncp5623c start -X -a 0x38
|
||||
|
||||
#mpu6000 -s -R 4 -T 20608 start
|
||||
mpu9250 -R 4 start
|
||||
|
@ -34,7 +34,7 @@ fi
|
|||
if param compare SYS_AUTOSTART 4071
|
||||
then
|
||||
# IFO GPS LED
|
||||
rgbled_ncp5623c start -a 0x38
|
||||
rgbled_ncp5623c start -X -a 0x38
|
||||
|
||||
# IFO rgb LED
|
||||
pca9685 start
|
||||
|
|
|
@ -55,7 +55,7 @@ mpu9250 start
|
|||
|
||||
gps start -d /dev/ttyS2 -s -p ubx
|
||||
|
||||
#rgbled start -b 1
|
||||
#rgbled start -I -b 1
|
||||
|
||||
adc start
|
||||
battery_status start
|
||||
|
|
|
@ -55,7 +55,7 @@ mpu9250 start
|
|||
|
||||
gps start -d /dev/ttyS2 -s -p ubx
|
||||
|
||||
#rgbled start -b 1
|
||||
#rgbled start -I -b 1
|
||||
|
||||
adc start
|
||||
battery_status start
|
||||
|
|
|
@ -55,7 +55,3 @@ static_assert(led_control_s::ORB_QUEUE_LENGTH >= BOARD_MAX_LEDS, "led_control_s:
|
|||
#error "BOARD_MAX_LEDS too large. You need to change the led_mask type in the led_control uorb topic (and where it's used)"
|
||||
#endif
|
||||
|
||||
// Legacy paths - 2 are need to allow both pwm and i2c drviers to co-exist
|
||||
#define RGBLED0_DEVICE_PATH "/dev/rgbled0" // Primary RGB LED on i2c
|
||||
#define RGBLED1_DEVICE_PATH "/dev/rgbled1" // Primary RGB LED(NCP5623C) on i2c
|
||||
#define RGBLED_PWM0_DEVICE_PATH "/dev/rgbled_pwm0" // Secondary RGB LED on PWM
|
||||
|
|
|
@ -138,6 +138,9 @@
|
|||
#define DRV_DIST_DEVTYPE_VL53LXX 0x76
|
||||
#define DRV_POWER_DEVTYPE_INA226 0x77
|
||||
#define DRV_POWER_DEVTYPE_VOXLPM 0x78
|
||||
#define DRV_LED_DEVTYPE_BLINKM 0x79
|
||||
#define DRV_LED_DEVTYPE_RGBLED 0x7a
|
||||
#define DRV_LED_DEVTYPE_RGBLED_NCP5623C 0x7b
|
||||
|
||||
#define DRV_DEVTYPE_UNUSED 0xff
|
||||
|
||||
|
|
|
@ -99,7 +99,8 @@
|
|||
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/drv_blinkm.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
|
@ -113,12 +114,17 @@ static const int LED_OFFTIME = 120;
|
|||
static const int LED_BLINK = 1;
|
||||
static const int LED_NOBLINK = 0;
|
||||
|
||||
class BlinkM : public device::I2C, public px4::ScheduledWorkItem
|
||||
class BlinkM : public device::I2C, public I2CSPIDriver<BlinkM>
|
||||
{
|
||||
public:
|
||||
BlinkM(int bus, int blinkm);
|
||||
BlinkM(I2CSPIBusOption bus_option, const int bus, int bus_frequency, const int address);
|
||||
virtual ~BlinkM() = default;
|
||||
|
||||
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance);
|
||||
static void print_usage();
|
||||
|
||||
void custom_method(const BusCLIArguments &cli) override;
|
||||
|
||||
virtual int init();
|
||||
virtual int probe();
|
||||
|
@ -127,6 +133,7 @@ public:
|
|||
|
||||
static const char *const script_names[];
|
||||
|
||||
void RunImpl();
|
||||
private:
|
||||
enum ScriptID {
|
||||
USER = 0,
|
||||
|
@ -196,8 +203,6 @@ private:
|
|||
|
||||
void setLEDColor(int ledcolor);
|
||||
|
||||
void Run() override;
|
||||
|
||||
int set_rgb(uint8_t r, uint8_t g, uint8_t b);
|
||||
|
||||
int fade_rgb(uint8_t r, uint8_t g, uint8_t b);
|
||||
|
@ -221,12 +226,6 @@ private:
|
|||
int get_firmware_version(uint8_t version[2]);
|
||||
};
|
||||
|
||||
/* for now, we only support one BlinkM */
|
||||
namespace
|
||||
{
|
||||
BlinkM *g_blinkm;
|
||||
}
|
||||
|
||||
/* list of script names, must match script ID numbers */
|
||||
const char *const BlinkM::script_names[] = {
|
||||
"USER",
|
||||
|
@ -254,9 +253,9 @@ const char *const BlinkM::script_names[] = {
|
|||
|
||||
extern "C" __EXPORT int blinkm_main(int argc, char *argv[]);
|
||||
|
||||
BlinkM::BlinkM(int bus, int blinkm) :
|
||||
I2C("blinkm", BLINKM0_DEVICE_PATH, bus, blinkm, 100000),
|
||||
ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(get_device_id())),
|
||||
BlinkM::BlinkM(I2CSPIBusOption bus_option, const int bus, int bus_frequency, const int address) :
|
||||
I2C("blinkm", BLINKM0_DEVICE_PATH, bus, address, bus_frequency),
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
|
||||
led_color_1(LED_OFF),
|
||||
led_color_2(LED_OFF),
|
||||
led_color_3(LED_OFF),
|
||||
|
@ -382,7 +381,7 @@ BlinkM::ioctl(device::file_t *filp, int cmd, unsigned long arg)
|
|||
|
||||
|
||||
void
|
||||
BlinkM::Run()
|
||||
BlinkM::RunImpl()
|
||||
{
|
||||
if (led_thread_ready == true) {
|
||||
if (!detected_cells_blinked) {
|
||||
|
@ -924,111 +923,117 @@ BlinkM::get_firmware_version(uint8_t version[2])
|
|||
return transfer(&msg, sizeof(msg), version, 2);
|
||||
}
|
||||
|
||||
void blinkm_usage();
|
||||
|
||||
void blinkm_usage()
|
||||
void
|
||||
BlinkM::print_usage()
|
||||
{
|
||||
warnx("missing command: try 'start', 'systemstate', 'ledoff', 'list' or a script name {options}");
|
||||
warnx("options:");
|
||||
warnx("\t-b --bus i2cbus (3)");
|
||||
warnx("\t-a --blinkmaddr blinkmaddr (9)");
|
||||
PRINT_MODULE_USAGE_NAME("blinkm", "driver");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(9);
|
||||
PRINT_MODULE_USAGE_COMMAND("systemstate");
|
||||
PRINT_MODULE_USAGE_COMMAND("ledoff");
|
||||
PRINT_MODULE_USAGE_COMMAND("list");
|
||||
PRINT_MODULE_USAGE_COMMAND("script");
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('n', nullptr, "<file>", "Script file name", false);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
int
|
||||
blinkm_main(int argc, char *argv[])
|
||||
I2CSPIDriverBase *BlinkM::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance)
|
||||
{
|
||||
BlinkM *instance = new BlinkM(iterator.configuredBusOption(), iterator.bus(), cli.bus_frequency, cli.i2c_address);
|
||||
|
||||
int i2cdevice = PX4_I2C_BUS_EXPANSION;
|
||||
int blinkmadr = 9;
|
||||
|
||||
int x;
|
||||
|
||||
if (argc < 2) {
|
||||
blinkm_usage();
|
||||
return 1;
|
||||
if (instance == nullptr) {
|
||||
PX4_ERR("alloc failed");
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
for (x = 1; x < argc; x++) {
|
||||
if (strcmp(argv[x], "-b") == 0 || strcmp(argv[x], "--bus") == 0) {
|
||||
if (argc > x + 1) {
|
||||
i2cdevice = atoi(argv[x + 1]);
|
||||
}
|
||||
if (instance->init() != PX4_OK) {
|
||||
delete instance;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
return instance;
|
||||
}
|
||||
|
||||
void
|
||||
BlinkM::custom_method(const BusCLIArguments &cli)
|
||||
{
|
||||
setMode(cli.custom1);
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int blinkm_main(int argc, char *argv[])
|
||||
{
|
||||
int ch;
|
||||
using ThisDriver = BlinkM;
|
||||
BusCLIArguments cli{true, false};
|
||||
cli.default_i2c_frequency = 100000;
|
||||
cli.i2c_address = 9;
|
||||
const char *script = nullptr;
|
||||
|
||||
while ((ch = cli.getopt(argc, argv, "n:")) != EOF) {
|
||||
switch (ch) {
|
||||
case 'n':
|
||||
script = cli.optarg();
|
||||
break;
|
||||
}
|
||||
|
||||
if (strcmp(argv[x], "-a") == 0 || strcmp(argv[x], "--blinkmaddr") == 0) {
|
||||
if (argc > x + 1) {
|
||||
blinkmadr = atoi(argv[x + 1]);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
if (g_blinkm != nullptr) {
|
||||
warnx("already started");
|
||||
return 1;
|
||||
}
|
||||
const char *verb = cli.optarg();
|
||||
|
||||
g_blinkm = new BlinkM(i2cdevice, blinkmadr);
|
||||
|
||||
if (g_blinkm == nullptr) {
|
||||
warnx("new failed");
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (OK != g_blinkm->init()) {
|
||||
delete g_blinkm;
|
||||
g_blinkm = nullptr;
|
||||
warnx("init failed");
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
if (!verb) {
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_LED_DEVTYPE_BLINKM);
|
||||
|
||||
if (g_blinkm == nullptr) {
|
||||
PX4_ERR("not started");
|
||||
blinkm_usage();
|
||||
return 0;
|
||||
if (!strcmp(verb, "start")) {
|
||||
return ThisDriver::module_start(cli, iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "systemstate")) {
|
||||
g_blinkm->setMode(1);
|
||||
return 0;
|
||||
if (!strcmp(verb, "stop")) {
|
||||
return ThisDriver::module_stop(iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "ledoff")) {
|
||||
g_blinkm->setMode(0);
|
||||
return 0;
|
||||
if (!strcmp(verb, "status")) {
|
||||
return ThisDriver::module_status(iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "systemstate")) {
|
||||
cli.custom1 = 1;
|
||||
return ThisDriver::module_custom_method(cli, iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "list")) {
|
||||
if (!strcmp(verb, "ledoff")) {
|
||||
cli.custom1 = 0;
|
||||
return ThisDriver::module_custom_method(cli, iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "list")) {
|
||||
for (unsigned i = 0; BlinkM::script_names[i] != nullptr; i++) {
|
||||
PX4_ERR(" %s", BlinkM::script_names[i]);
|
||||
PX4_INFO(" %s", BlinkM::script_names[i]);
|
||||
}
|
||||
|
||||
PX4_ERR(" <html color number>");
|
||||
PX4_INFO(" <html color number>");
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* things that require access to the device */
|
||||
int fd = px4_open(BLINKM0_DEVICE_PATH, 0);
|
||||
if (!strcmp(verb, "script") && script) {
|
||||
/* things that require access to the device */
|
||||
int fd = px4_open(BLINKM0_DEVICE_PATH, 0);
|
||||
|
||||
if (fd < 0) {
|
||||
warn("can't open BlinkM device");
|
||||
return 1;
|
||||
}
|
||||
if (fd < 0) {
|
||||
PX4_ERR("can't open BlinkM device");
|
||||
return 1;
|
||||
}
|
||||
|
||||
g_blinkm->setMode(0);
|
||||
px4_ioctl(fd, BLINKM_PLAY_SCRIPT_NAMED, (unsigned long)script);
|
||||
|
||||
if (px4_ioctl(fd, BLINKM_PLAY_SCRIPT_NAMED, (unsigned long)argv[1]) == OK) {
|
||||
px4_close(fd);
|
||||
return 0;
|
||||
}
|
||||
|
||||
px4_close(fd);
|
||||
|
||||
blinkm_usage();
|
||||
return 0;
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
|
|
@ -46,7 +46,8 @@
|
|||
#include <lib/led/led.h>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
|
||||
|
@ -60,16 +61,23 @@
|
|||
#define SETTING_NOT_POWERSAVE 0x01 /**< power-save mode not off */
|
||||
#define SETTING_ENABLE 0x02 /**< on */
|
||||
|
||||
class RGBLED : public device::I2C, public px4::ScheduledWorkItem
|
||||
class RGBLED : public device::I2C, public I2CSPIDriver<RGBLED>
|
||||
{
|
||||
public:
|
||||
RGBLED(int bus, int rgbled);
|
||||
virtual ~RGBLED();
|
||||
RGBLED(I2CSPIBusOption bus_option, const int bus, int bus_frequency, const int address);
|
||||
virtual ~RGBLED() = default;
|
||||
|
||||
virtual int init();
|
||||
virtual int probe();
|
||||
int status();
|
||||
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance);
|
||||
static void print_usage();
|
||||
|
||||
int init() override;
|
||||
int probe() override;
|
||||
|
||||
void RunImpl();
|
||||
|
||||
protected:
|
||||
void print_status() override;
|
||||
private:
|
||||
|
||||
float _brightness{1.0f};
|
||||
|
@ -78,15 +86,12 @@ private:
|
|||
uint8_t _r{0};
|
||||
uint8_t _g{0};
|
||||
uint8_t _b{0};
|
||||
volatile bool _running{false};
|
||||
volatile bool _should_run{true};
|
||||
bool _leds_enabled{true};
|
||||
|
||||
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
|
||||
|
||||
LedController _led_controller;
|
||||
|
||||
void Run() override;
|
||||
|
||||
int send_led_enable(bool enable);
|
||||
int send_led_rgb();
|
||||
|
@ -94,30 +99,10 @@ private:
|
|||
void update_params();
|
||||
};
|
||||
|
||||
/* for now, we only support one RGBLED */
|
||||
namespace
|
||||
RGBLED::RGBLED(I2CSPIBusOption bus_option, const int bus, int bus_frequency, const int address) :
|
||||
I2C("rgbled", nullptr, bus, address, bus_frequency),
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus)
|
||||
{
|
||||
RGBLED *g_rgbled = nullptr;
|
||||
}
|
||||
|
||||
void rgbled_usage();
|
||||
|
||||
extern "C" __EXPORT int rgbled_main(int argc, char *argv[]);
|
||||
|
||||
RGBLED::RGBLED(int bus, int rgbled) :
|
||||
I2C("rgbled", RGBLED0_DEVICE_PATH, bus, rgbled, 100000),
|
||||
ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(get_device_id()))
|
||||
{
|
||||
}
|
||||
|
||||
RGBLED::~RGBLED()
|
||||
{
|
||||
_should_run = false;
|
||||
int counter = 0;
|
||||
|
||||
while (_running && ++counter < 10) {
|
||||
px4_usleep(100000);
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
|
@ -135,8 +120,6 @@ RGBLED::init()
|
|||
|
||||
update_params();
|
||||
|
||||
_running = true;
|
||||
|
||||
// kick off work queue
|
||||
ScheduleNow();
|
||||
|
||||
|
@ -173,8 +156,8 @@ RGBLED::probe()
|
|||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
RGBLED::status()
|
||||
void
|
||||
RGBLED::print_status()
|
||||
{
|
||||
bool on, powersave;
|
||||
uint8_t r, g, b;
|
||||
|
@ -183,27 +166,17 @@ RGBLED::status()
|
|||
|
||||
if (ret == OK) {
|
||||
/* we don't care about power-save mode */
|
||||
DEVICE_LOG("state: %s", on ? "ON" : "OFF");
|
||||
DEVICE_LOG("red: %u, green: %u, blue: %u", (unsigned)r, (unsigned)g, (unsigned)b);
|
||||
PX4_INFO("state: %s", on ? "ON" : "OFF");
|
||||
PX4_INFO("red: %u, green: %u, blue: %u", (unsigned)r, (unsigned)g, (unsigned)b);
|
||||
|
||||
} else {
|
||||
PX4_WARN("failed to read led");
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* Main loop function
|
||||
*/
|
||||
void
|
||||
RGBLED::Run()
|
||||
RGBLED::RunImpl()
|
||||
{
|
||||
if (!_should_run) {
|
||||
_running = false;
|
||||
return;
|
||||
}
|
||||
|
||||
// check for parameter updates
|
||||
if (_parameter_update_sub.updated()) {
|
||||
// clear update
|
||||
|
@ -349,113 +322,61 @@ RGBLED::update_params()
|
|||
}
|
||||
|
||||
void
|
||||
rgbled_usage()
|
||||
RGBLED::print_usage()
|
||||
{
|
||||
PX4_INFO("missing command: try 'start', 'status', 'stop'");
|
||||
PX4_INFO("options:");
|
||||
PX4_INFO(" -b i2cbus (%d)", PX4_I2C_BUS_LED);
|
||||
PX4_INFO(" -a addr (0x%x)", ADDR);
|
||||
PRINT_MODULE_USAGE_NAME("rgbled", "driver");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x55);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
int
|
||||
rgbled_main(int argc, char *argv[])
|
||||
I2CSPIDriverBase *RGBLED::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance)
|
||||
{
|
||||
int i2cdevice = -1;
|
||||
int rgbledadr = ADDR; /* 7bit */
|
||||
RGBLED *instance = new RGBLED(iterator.configuredBusOption(), iterator.bus(), cli.bus_frequency, cli.i2c_address);
|
||||
|
||||
int ch;
|
||||
|
||||
/* jump over start/off/etc and look at options first */
|
||||
int myoptind = 1;
|
||||
const char *myoptarg = nullptr;
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "a:b:", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'a':
|
||||
rgbledadr = strtol(myoptarg, nullptr, 0);
|
||||
break;
|
||||
|
||||
case 'b':
|
||||
i2cdevice = strtol(myoptarg, nullptr, 0);
|
||||
break;
|
||||
|
||||
default:
|
||||
rgbled_usage();
|
||||
return 1;
|
||||
}
|
||||
if (instance == nullptr) {
|
||||
PX4_ERR("alloc failed");
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
if (myoptind >= argc) {
|
||||
rgbled_usage();
|
||||
return 1;
|
||||
if (instance->init() != PX4_OK) {
|
||||
delete instance;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
const char *verb = argv[myoptind];
|
||||
return instance;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int rgbled_main(int argc, char *argv[])
|
||||
{
|
||||
using ThisDriver = RGBLED;
|
||||
BusCLIArguments cli{true, false};
|
||||
cli.default_i2c_frequency = 100000;
|
||||
cli.i2c_address = ADDR;
|
||||
|
||||
const char *verb = cli.parseDefaultArguments(argc, argv);
|
||||
|
||||
if (!verb) {
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_LED_DEVTYPE_RGBLED);
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
if (g_rgbled != nullptr) {
|
||||
PX4_WARN("already started");
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (i2cdevice == -1) {
|
||||
// try the external bus first
|
||||
i2cdevice = PX4_I2C_BUS_EXPANSION;
|
||||
g_rgbled = new RGBLED(PX4_I2C_BUS_EXPANSION, rgbledadr);
|
||||
|
||||
if (g_rgbled != nullptr && OK != g_rgbled->init()) {
|
||||
delete g_rgbled;
|
||||
g_rgbled = nullptr;
|
||||
}
|
||||
|
||||
if (g_rgbled == nullptr) {
|
||||
// fall back to default bus
|
||||
if (PX4_I2C_BUS_LED == PX4_I2C_BUS_EXPANSION) {
|
||||
PX4_WARN("no RGB led on bus #%d", i2cdevice);
|
||||
return 1;
|
||||
}
|
||||
|
||||
i2cdevice = PX4_I2C_BUS_LED;
|
||||
}
|
||||
}
|
||||
|
||||
if (g_rgbled == nullptr) {
|
||||
g_rgbled = new RGBLED(i2cdevice, rgbledadr);
|
||||
|
||||
if (g_rgbled == nullptr) {
|
||||
PX4_WARN("alloc failed");
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (OK != g_rgbled->init()) {
|
||||
delete g_rgbled;
|
||||
g_rgbled = nullptr;
|
||||
PX4_WARN("no RGB led on bus #%d", i2cdevice);
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* need the driver past this point */
|
||||
if (g_rgbled == nullptr) {
|
||||
PX4_WARN("not started");
|
||||
rgbled_usage();
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "status")) {
|
||||
g_rgbled->status();
|
||||
return 0;
|
||||
return ThisDriver::module_start(cli, iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "stop")) {
|
||||
delete g_rgbled;
|
||||
g_rgbled = nullptr;
|
||||
return 0;
|
||||
return ThisDriver::module_stop(iterator);
|
||||
}
|
||||
|
||||
rgbled_usage();
|
||||
return 1;
|
||||
if (!strcmp(verb, "status")) {
|
||||
return ThisDriver::module_status(iterator);
|
||||
}
|
||||
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
|
|
@ -45,7 +45,8 @@
|
|||
#include <lib/led/led.h>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
|
||||
|
@ -61,14 +62,20 @@
|
|||
#define NCP5623_LED_OFF 0x00 /**< off */
|
||||
|
||||
|
||||
class RGBLED_NPC5623C : public device::I2C, public px4::ScheduledWorkItem
|
||||
class RGBLED_NPC5623C : public device::I2C, public I2CSPIDriver<RGBLED_NPC5623C>
|
||||
{
|
||||
public:
|
||||
RGBLED_NPC5623C(int bus, int rgbled);
|
||||
virtual ~RGBLED_NPC5623C();
|
||||
RGBLED_NPC5623C(I2CSPIBusOption bus_option, const int bus, int bus_frequency, const int address);
|
||||
virtual ~RGBLED_NPC5623C() = default;
|
||||
|
||||
virtual int init();
|
||||
virtual int probe();
|
||||
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance);
|
||||
static void print_usage();
|
||||
|
||||
int init() override;
|
||||
int probe() override;
|
||||
|
||||
void RunImpl();
|
||||
|
||||
private:
|
||||
|
||||
|
@ -86,38 +93,16 @@ private:
|
|||
|
||||
LedController _led_controller;
|
||||
|
||||
void Run() override;
|
||||
|
||||
int send_led_rgb();
|
||||
void update_params();
|
||||
|
||||
int write(uint8_t reg, uint8_t data);
|
||||
};
|
||||
|
||||
/* for now, we only support one RGBLED */
|
||||
namespace
|
||||
RGBLED_NPC5623C::RGBLED_NPC5623C(I2CSPIBusOption bus_option, const int bus, int bus_frequency, const int address) :
|
||||
I2C("rgbled1", nullptr, bus, address, bus_frequency),
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus)
|
||||
{
|
||||
RGBLED_NPC5623C *g_rgbled = nullptr;
|
||||
}
|
||||
|
||||
void rgbled_ncp5623c_usage();
|
||||
|
||||
extern "C" __EXPORT int rgbled_ncp5623c_main(int argc, char *argv[]);
|
||||
|
||||
RGBLED_NPC5623C::RGBLED_NPC5623C(int bus, int rgbled) :
|
||||
I2C("rgbled1", RGBLED1_DEVICE_PATH, bus, rgbled, 100000),
|
||||
ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(get_device_id()))
|
||||
{
|
||||
}
|
||||
|
||||
RGBLED_NPC5623C::~RGBLED_NPC5623C()
|
||||
{
|
||||
_should_run = false;
|
||||
int counter = 0;
|
||||
|
||||
while (_running && ++counter < 10) {
|
||||
px4_usleep(100000);
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
|
@ -157,17 +142,9 @@ RGBLED_NPC5623C::probe()
|
|||
return write(NCP5623_LED_CURRENT, 0x00);
|
||||
}
|
||||
|
||||
/**
|
||||
* Main loop function
|
||||
*/
|
||||
void
|
||||
RGBLED_NPC5623C::Run()
|
||||
RGBLED_NPC5623C::RunImpl()
|
||||
{
|
||||
if (!_should_run) {
|
||||
_running = false;
|
||||
return;
|
||||
}
|
||||
|
||||
// check for parameter updates
|
||||
if (_parameter_update_sub.updated()) {
|
||||
// clear update
|
||||
|
@ -262,108 +239,63 @@ RGBLED_NPC5623C::update_params()
|
|||
}
|
||||
|
||||
void
|
||||
rgbled_ncp5623c_usage()
|
||||
RGBLED_NPC5623C::print_usage()
|
||||
{
|
||||
PX4_INFO("missing command: try 'start', 'stop'");
|
||||
PX4_INFO("options:");
|
||||
PX4_INFO(" -b i2cbus (%d)", PX4_I2C_BUS_LED);
|
||||
PX4_INFO(" -a addr (0x%x)", ADDR);
|
||||
PRINT_MODULE_USAGE_NAME("rgbled", "driver");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x39);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
int
|
||||
rgbled_ncp5623c_main(int argc, char *argv[])
|
||||
I2CSPIDriverBase *RGBLED_NPC5623C::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance)
|
||||
{
|
||||
int i2cdevice = -1;
|
||||
int rgbledadr = ADDR; /* 7bit */
|
||||
RGBLED_NPC5623C *instance = new RGBLED_NPC5623C(iterator.configuredBusOption(), iterator.bus(), cli.bus_frequency,
|
||||
cli.i2c_address);
|
||||
|
||||
int ch;
|
||||
|
||||
/* jump over start/off/etc and look at options first */
|
||||
int myoptind = 1;
|
||||
const char *myoptarg = nullptr;
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "a:b:", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'a':
|
||||
rgbledadr = strtol(myoptarg, nullptr, 0);
|
||||
break;
|
||||
|
||||
case 'b':
|
||||
i2cdevice = strtol(myoptarg, nullptr, 0);
|
||||
break;
|
||||
|
||||
default:
|
||||
rgbled_ncp5623c_usage();
|
||||
return 1;
|
||||
}
|
||||
if (instance == nullptr) {
|
||||
PX4_ERR("alloc failed");
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
if (myoptind >= argc) {
|
||||
rgbled_ncp5623c_usage();
|
||||
return 1;
|
||||
if (instance->init() != PX4_OK) {
|
||||
delete instance;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
const char *verb = argv[myoptind];
|
||||
return instance;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int rgbled_ncp5623c_main(int argc, char *argv[])
|
||||
{
|
||||
using ThisDriver = RGBLED_NPC5623C;
|
||||
BusCLIArguments cli{true, false};
|
||||
cli.default_i2c_frequency = 100000;
|
||||
cli.i2c_address = ADDR;
|
||||
|
||||
const char *verb = cli.parseDefaultArguments(argc, argv);
|
||||
|
||||
if (!verb) {
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
BusInstanceIterator iterator(MODULE_NAME, cli,
|
||||
DRV_LED_DEVTYPE_RGBLED_NCP5623C);
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
if (g_rgbled != nullptr) {
|
||||
PX4_WARN("already started");
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (i2cdevice == -1) {
|
||||
// try the external bus first
|
||||
i2cdevice = PX4_I2C_BUS_EXPANSION;
|
||||
g_rgbled = new RGBLED_NPC5623C(PX4_I2C_BUS_EXPANSION, rgbledadr);
|
||||
|
||||
if (g_rgbled != nullptr && OK != g_rgbled->init()) {
|
||||
delete g_rgbled;
|
||||
g_rgbled = nullptr;
|
||||
}
|
||||
|
||||
if (g_rgbled == nullptr) {
|
||||
// fall back to default bus
|
||||
if (PX4_I2C_BUS_LED == PX4_I2C_BUS_EXPANSION) {
|
||||
PX4_WARN("no RGB led on bus #%d", i2cdevice);
|
||||
return 1;
|
||||
}
|
||||
|
||||
i2cdevice = PX4_I2C_BUS_LED;
|
||||
}
|
||||
}
|
||||
|
||||
if (g_rgbled == nullptr) {
|
||||
g_rgbled = new RGBLED_NPC5623C(i2cdevice, rgbledadr);
|
||||
|
||||
if (g_rgbled == nullptr) {
|
||||
PX4_WARN("alloc failed");
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (OK != g_rgbled->init()) {
|
||||
delete g_rgbled;
|
||||
g_rgbled = nullptr;
|
||||
PX4_WARN("no RGB led on bus #%d", i2cdevice);
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* need the driver past this point */
|
||||
if (g_rgbled == nullptr) {
|
||||
PX4_WARN("not started");
|
||||
rgbled_ncp5623c_usage();
|
||||
return 1;
|
||||
return ThisDriver::module_start(cli, iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "stop")) {
|
||||
delete g_rgbled;
|
||||
g_rgbled = nullptr;
|
||||
return 0;
|
||||
return ThisDriver::module_stop(iterator);
|
||||
}
|
||||
|
||||
rgbled_ncp5623c_usage();
|
||||
return 1;
|
||||
if (!strcmp(verb, "status")) {
|
||||
return ThisDriver::module_status(iterator);
|
||||
}
|
||||
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue