drivers/uavcan: RGB LED support (publish uavcan::equipment::indication::LightsCommand)

Co-authored-by: Alex Mikhalev <alexmikhalevalex@gmail.com>
This commit is contained in:
Daniel Agar 2020-10-17 12:33:09 -04:00 committed by GitHub
parent 70b67ddbff
commit 224be8ba24
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
5 changed files with 198 additions and 0 deletions

View File

@ -121,6 +121,9 @@ px4_add_module(
${LIBUAVCAN_DIR}/libuavcan_drivers/posix/include
${LIBUAVCAN_DIR_DRIVERS}/${UAVCAN_DRIVER}/driver/include
SRCS
rgbled.cpp
rgbled.hpp
# Main
uavcan_main.cpp
uavcan_servers.cpp
@ -143,6 +146,7 @@ px4_add_module(
DEPENDS
px4_uavcan_dsdlc
led
mixer
mixer_module
output_limit

View File

@ -0,0 +1,121 @@
/****************************************************************************
*
* Copyright (C) 2020 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. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions 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.
*
****************************************************************************/
#include "rgbled.hpp"
UavcanRGBController::UavcanRGBController(uavcan::INode &node) :
_node(node),
_uavcan_pub_lights_cmd(node),
_timer(node)
{
_uavcan_pub_lights_cmd.setPriority(uavcan::TransferPriority::Lowest);
}
int UavcanRGBController::init()
{
// Setup timer and call back function for periodic updates
_timer.setCallback(TimerCbBinder(this, &UavcanRGBController::periodic_update));
_timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ));
return 0;
}
void UavcanRGBController::periodic_update(const uavcan::TimerEvent &)
{
LedControlData led_control_data;
if (_led_controller.update(led_control_data) == 1) {
// RGB color in the standard 5-6-5 16-bit palette.
// Monocolor lights should interpret this as brightness setpoint: from zero (0, 0, 0) to full brightness (31, 63, 31).
uavcan::equipment::indication::SingleLightCommand cmd;
uint8_t brightness = led_control_data.leds[0].brightness;
switch (led_control_data.leds[0].color) {
case led_control_s::COLOR_RED:
cmd.color.red = brightness >> 3;
cmd.color.green = 0;
cmd.color.blue = 0;
break;
case led_control_s::COLOR_GREEN:
cmd.color.red = 0;
cmd.color.green = brightness >> 2;
cmd.color.blue = 0;
break;
case led_control_s::COLOR_BLUE:
cmd.color.red = 0;
cmd.color.green = 0;
cmd.color.blue = brightness >> 3;
break;
case led_control_s::COLOR_AMBER: // make it the same as yellow
// FALLTHROUGH
case led_control_s::COLOR_YELLOW:
cmd.color.red = brightness >> 3;
cmd.color.green = brightness >> 2;
cmd.color.blue = 0;
break;
case led_control_s::COLOR_PURPLE:
cmd.color.red = brightness >> 3;
cmd.color.green = 0;
cmd.color.blue = brightness >> 3;
break;
case led_control_s::COLOR_CYAN:
cmd.color.red = 0;
cmd.color.green = brightness >> 2;
cmd.color.blue = brightness >> 3;
break;
case led_control_s::COLOR_WHITE:
cmd.color.red = brightness >> 3;
cmd.color.green = brightness >> 2;
cmd.color.blue = brightness >> 3;
break;
default: // led_control_s::COLOR_OFF
cmd.color.red = 0;
cmd.color.green = 0;
cmd.color.blue = 0;
break;
}
uavcan::equipment::indication::LightsCommand cmds;
cmds.commands.push_back(cmd);
_uavcan_pub_lights_cmd.broadcast(cmds);
}
}

View File

@ -0,0 +1,64 @@
/****************************************************************************
*
* Copyright (C) 2020 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. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions 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.
*
****************************************************************************/
#pragma once
#include <uavcan/uavcan.hpp>
#include <uavcan/equipment/indication/LightsCommand.hpp>
#include <lib/led/led.h>
class UavcanRGBController
{
public:
UavcanRGBController(uavcan::INode &node);
~UavcanRGBController() = default;
// setup periodic updater
int init();
private:
// Max update rate to avoid exessive bus traffic
static constexpr unsigned MAX_RATE_HZ = 20;
void periodic_update(const uavcan::TimerEvent &);
typedef uavcan::MethodBinder<UavcanRGBController *, void (UavcanRGBController::*)(const uavcan::TimerEvent &)>
TimerCbBinder;
uavcan::INode &_node;
uavcan::Publisher<uavcan::equipment::indication::LightsCommand> _uavcan_pub_lights_cmd;
uavcan::TimerEventForwarder<TimerCbBinder> _timer;
LedController _led_controller;
};

View File

@ -82,6 +82,7 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys
_node(can_driver, system_clock, _pool_allocator),
_esc_controller(_node),
_hardpoint_controller(_node),
_rgbled_controller(_node),
_time_sync_master(_node),
_time_sync_slave(_node),
_node_status_monitor(_node),
@ -621,6 +622,12 @@ UavcanNode::init(uavcan::NodeID node_id, UAVCAN_DRIVER::BusEvent &bus_events)
return ret;
}
ret = _rgbled_controller.init();
if (ret < 0) {
return ret;
}
// Sensor bridges
IUavcanSensorBridge::make_all(_node, _sensor_bridges);

View File

@ -46,6 +46,7 @@
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include "rgbled.hpp"
#include "uavcan_driver.hpp"
#include "uavcan_servers.hpp"
#include "allocator.hpp"
@ -200,6 +201,7 @@ private:
UavcanEscController _esc_controller;
UavcanMixingInterface _mixing_interface{_node_mutex, _esc_controller};
UavcanHardpointController _hardpoint_controller;
UavcanRGBController _rgbled_controller;
uavcan::GlobalTimeSyncMaster _time_sync_master;
uavcan::GlobalTimeSyncSlave _time_sync_slave;
uavcan::NodeStatusMonitor _node_status_monitor;