Go to the documentation of this file.
35 #include <fadecandy_msgs/LEDArray.h>
65 ROS_INFO(
"Fadecandy device is connected.");
67 catch (
const std::exception& e)
80 std::vector<std::vector<Color>> led_array_colors;
81 for (
const auto& strip : led_array_msg->strips)
83 std::vector<Color> led_strip_colors;
84 for (
const auto& color : strip.colors)
86 led_strip_colors.emplace_back(
static_cast<int>(color.r * 255),
static_cast<int>(color.g * 255),
87 static_cast<int>(color.b * 255));
89 led_array_colors.push_back(led_strip_colors);
96 catch (
const std::exception& e)
98 ROS_ERROR(
"Error occured: %s ", e.what());
106 diagnostic_status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Connected");
110 diagnostic_status.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Disconnected");
FadecandyDriver driver_
driver_ Fadecandy driver
std::string connect()
connect Initialize the Fadecandy device
void run()
run Listen to LED messages and publishes diagnostic of the driver
#define ROS_WARN_ONCE(...)
void setLedsCallback(const fadecandy_msgs::LEDArrayConstPtr &msg)
double restart_patience_
restart_patience_ Restart patience time
ros::Subscriber led_subscriber_
led_subscriber_ LED messages subscriber
diagnostic_updater::Updater diagnostic_updater_
diagnostic_updater_ Diagnostic updater
void summary(const diagnostic_msgs::DiagnosticStatus &src)
void connectTimerCallback(const ros::TimerEvent &e)
void setColors(std::vector< std::vector< Color >> led_colors)
setColors Transfer the LED color stream to the driver
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void setHardwareID(const std::string &hwid)
ros::Timer diagnostics_timer_
timer_ Periodic timer for updating the diagnostics
FadecandyDriverROS(double restart_patience)
FadecandyDriverRos fadecandy driver ROS wrapper.
void diagnosticsCallback(diagnostic_updater::DiagnosticStatusWrapper &diagnostic_status)
diagnosticsCallback Diagnostics callback
bool isConnected()
isConnected
ros::Timer connect_timer_
connection_check_timer_ Periodic timer for checking the connection
void add(const std::string &name, TaskFunction f)
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
void diagnosticsTimerCallback(const ros::TimerEvent &e)
void setupConnection()
setupConnection Connect the driver to the device