Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
led_controller::LedController Class Reference

LedController: a class that provides ROS interface for the LEDs. More...

Public Member Functions

 LedController (const std::string &robotNamespace)
 
void registerPlugin (sim_led::LedVisualPlugin *plugin, int ledIdx=0, int totalLeds=0)
 
void unregisterPlugin (sim_led::LedVisualPlugin *plugin)
 
 ~LedController ()
 

Private Types

enum  Role { Role::Client, Role::Server }
 Role for the current controller. More...
 

Private Member Functions

void handleLedsMsg (const led_msgs::LEDStateArrayConstPtr &leds)
 
bool setLeds (led_msgs::SetLEDs::Request &req, led_msgs::SetLEDs::Response &resp)
 

Private Attributes

led_msgs::LEDStateArray ledState
 
std::unique_ptr< ros::NodeHandlenh
 
std::vector< sim_led::LedVisualPlugin * > registeredLeds
 
std::mutex registryMutex
 
std::string robotNamespace
 
enum led_controller::LedController::Role role
 
ros::ServiceServer setLedsSrv
 
ros::Publisher statePublisher
 
ros::Subscriber stateSubscriber
 

Detailed Description

LedController: a class that provides ROS interface for the LEDs.

Definition at line 34 of file sim_leds.cpp.

Member Enumeration Documentation

◆ Role

Role for the current controller.

Enumerator
Client 
Server 

Definition at line 38 of file sim_leds.cpp.

Constructor & Destructor Documentation

◆ LedController()

led_controller::LedController::LedController ( const std::string &  robotNamespace)
inline

Definition at line 63 of file sim_leds.cpp.

◆ ~LedController()

led_controller::LedController::~LedController ( )
inline

Definition at line 88 of file sim_leds.cpp.

Member Function Documentation

◆ handleLedsMsg()

void led_controller::LedController::handleLedsMsg ( const led_msgs::LEDStateArrayConstPtr &  leds)
private

Definition at line 218 of file sim_leds.cpp.

◆ registerPlugin()

void led_controller::LedController::registerPlugin ( sim_led::LedVisualPlugin plugin,
int  ledIdx = 0,
int  totalLeds = 0 
)
inline

Definition at line 93 of file sim_leds.cpp.

◆ setLeds()

bool led_controller::LedController::setLeds ( led_msgs::SetLEDs::Request &  req,
led_msgs::SetLEDs::Response &  resp 
)
private

Definition at line 199 of file sim_leds.cpp.

◆ unregisterPlugin()

void led_controller::LedController::unregisterPlugin ( sim_led::LedVisualPlugin plugin)
inline

Definition at line 108 of file sim_leds.cpp.

Member Data Documentation

◆ ledState

led_msgs::LEDStateArray led_controller::LedController::ledState
private

Definition at line 54 of file sim_leds.cpp.

◆ nh

std::unique_ptr<ros::NodeHandle> led_controller::LedController::nh
private

Definition at line 50 of file sim_leds.cpp.

◆ registeredLeds

std::vector<sim_led::LedVisualPlugin*> led_controller::LedController::registeredLeds
private

Definition at line 45 of file sim_leds.cpp.

◆ registryMutex

std::mutex led_controller::LedController::registryMutex
private

Definition at line 47 of file sim_leds.cpp.

◆ robotNamespace

std::string led_controller::LedController::robotNamespace
private

Definition at line 48 of file sim_leds.cpp.

◆ role

enum led_controller::LedController::Role led_controller::LedController::role
private

◆ setLedsSrv

ros::ServiceServer led_controller::LedController::setLedsSrv
private

Definition at line 52 of file sim_leds.cpp.

◆ statePublisher

ros::Publisher led_controller::LedController::statePublisher
private

Definition at line 55 of file sim_leds.cpp.

◆ stateSubscriber

ros::Subscriber led_controller::LedController::stateSubscriber
private

Definition at line 57 of file sim_leds.cpp.


The documentation for this class was generated from the following file:


clover_simulation
Author(s): Alexey Rogachevskiy, Andrey Ryabov, Arthur Golubtsov, Oleg Kalachev, Svyatoslav Zhuravlev
autogenerated on Mon Feb 28 2022 22:08:36