Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
LightBuoyPlugin Class Reference

Visual plugin for changing the color of some visual elements using ROS messages. This plugin accepts the following SDF parameters: More...

#include <light_buoy_plugin.hh>

Inheritance diagram for LightBuoyPlugin:
Inheritance graph
[legend]

Public Member Functions

void Load (gazebo::rendering::VisualPtr _parent, sdf::ElementPtr _sdf)
 

Private Types

using Colors_t = std::pair< std_msgs::ColorRGBA, std::string >
 
using Pattern_t = std::array< uint8_t, 4 >
 

Private Member Functions

bool ChangePattern (std_srvs::Trigger::Request &_req, std_srvs::Trigger::Response &_res)
 Callback for change pattern service, calls other changePattern internaly. More...
 
void ChangePattern (std::string &_message)
 Generate a new pattern and reset state to OFF. More...
 
bool ParseSDF (sdf::ElementPtr _sdf)
 Parse all SDF parameters. More...
 
void Update ()
 Display the next color in the sequence, or start over if at the end. More...
 

Static Private Member Functions

static std_msgs::ColorRGBA CreateColor (const double _r, const double _g, const double _b, const double _a)
 Creates a std_msgs::ColorRGBA message from 4 doubles. More...
 
static uint8_t IndexFromColor (const std::string &_color)
 Return the index of the color from its string. More...
 

Private Attributes

ros::ServiceServer changePatternServer
 Service to generate and display a new color sequence. More...
 
std::mutex mutex
 Locks state and pattern member variables. More...
 
ros::NodeHandle nh
 ROS Node handle. More...
 
std::string ns
 ROS namespace. More...
 
Pattern_t pattern
 The color pattern. More...
 
gazebo::rendering::ScenePtr scene
 Pointer to the scene node. More...
 
bool shuffleEnabled = true
 Whether shuffle is enabled via a ROS topic or not. More...
 
uint8_t state = 0u
 Track current index in pattern. More...
 
gazebo::common::Timer timer
 Timer used to switch colors every second. More...
 
std::string topic
 ROS topic. More...
 
gazebo::event::ConnectionPtr updateConnection
 Connects to rendering update event. More...
 
std::vector< std::string > visualNames
 Collection of visual names. More...
 
std::vector< gazebo::rendering::VisualPtr > visuals
 Pointer to the visual elements to modify. More...
 

Static Private Attributes

static const std::array< Colors_t, 5 > kColors
 List of the color options (red, green, blue, yellow and no color) with their string name for logging. More...
 

Detailed Description

Visual plugin for changing the color of some visual elements using ROS messages. This plugin accepts the following SDF parameters:

<color_1>: The first color of the sequence (RED, GREEN, BLUE, YELLOW). <color_2>: The second color of the sequence (RED, GREEN, BLUE, YELLOW). <color_3>: The third color of the sequence (RED, GREEN, BLUE, YELLOW). <shuffle>: True if the topic for shuffling the sequence is enabled. <robot_namespace>: The ROS namespace for this node. If not present, the model name without any "::"" will be used. E.g.: The plugin under a visual named "model1::my_submodel::link::visual" will use "model1" as namespace unless a value is specified. <topic>: The ROS topic used to request color changes. <visuals>: The collection of visuals that change in color. It accepts N elements of <visual> elements.

Here's an example: <plugin name="light_buoy_plugin" filename="liblight_buoy_plugin.so"> <color_1>RED</color_1> <color_2>GREEN</color_2> <color_3>BLUE</color_3> <visuals> <visual>robotx_light_buoy::base_link::panel_1</visual> <visual>robotx_light_buoy::base_link::panel_2</visual> <visual>robotx_light_buoy::base_link::panel_3</visual> </visuals> <shuffle>true</shuffle> <robot_namespace>light_buoy</robot_namespace> <topic>light_buoy/shuffle</topic> </plugin>

Definition at line 64 of file light_buoy_plugin.hh.

Member Typedef Documentation

using LightBuoyPlugin::Colors_t = std::pair<std_msgs::ColorRGBA, std::string>
private

Definition at line 110 of file light_buoy_plugin.hh.

using LightBuoyPlugin::Pattern_t = std::array<uint8_t, 4>
private

Definition at line 114 of file light_buoy_plugin.hh.

Member Function Documentation

bool LightBuoyPlugin::ChangePattern ( std_srvs::Trigger::Request &  _req,
std_srvs::Trigger::Response &  _res 
)
private

Callback for change pattern service, calls other changePattern internaly.

Parameters
[in]_reqNot used.
[out]_resThe Response containing a message with the new pattern.
Returns
True when the operation succeed or false otherwise.

Definition at line 207 of file light_buoy_plugin.cc.

void LightBuoyPlugin::ChangePattern ( std::string &  _message)
private

Generate a new pattern and reset state to OFF.

Parameters
[in,out]_messageThe current pattern in string format, where each color is represented with its initial letter. E.g.: "RYG".

Definition at line 217 of file light_buoy_plugin.cc.

std_msgs::ColorRGBA LightBuoyPlugin::CreateColor ( const double  _r,
const double  _g,
const double  _b,
const double  _a 
)
staticprivate

Creates a std_msgs::ColorRGBA message from 4 doubles.

Parameters
[in]_rRed.
[in]_gGreen.
[in]_bBlue.
[in]_aAlpha.
Returns
The ColorRGBA message.

Definition at line 30 of file light_buoy_plugin.cc.

uint8_t LightBuoyPlugin::IndexFromColor ( const std::string &  _color)
staticprivate

Return the index of the color from its string.

Parameters
[in]_colorThe color
Returns
The index in kColors.

Definition at line 42 of file light_buoy_plugin.cc.

void LightBuoyPlugin::Load ( gazebo::rendering::VisualPtr  _parent,
sdf::ElementPtr  _sdf 
)

Definition at line 57 of file light_buoy_plugin.cc.

bool LightBuoyPlugin::ParseSDF ( sdf::ElementPtr  _sdf)
private

Parse all SDF parameters.

Parameters
[in]_sdfSDF elements.

Definition at line 93 of file light_buoy_plugin.cc.

void LightBuoyPlugin::Update ( )
private

Display the next color in the sequence, or start over if at the end.

Parameters
[in]_eventNot used.

Definition at line 164 of file light_buoy_plugin.cc.

Member Data Documentation

ros::ServiceServer LightBuoyPlugin::changePatternServer
private

Service to generate and display a new color sequence.

Definition at line 130 of file light_buoy_plugin.hh.

const std::array< LightBuoyPlugin::Colors_t, 5 > LightBuoyPlugin::kColors
staticprivate
Initial value:
= {LightBuoyPlugin::Colors_t(CreateColor(1.0, 0.0, 0.0, 1.0), "RED"),
LightBuoyPlugin::Colors_t(CreateColor(0.0, 1.0, 0.0, 1.0), "GREEN"),
LightBuoyPlugin::Colors_t(CreateColor(0.0, 0.0, 1.0, 1.0), "BLUE"),
LightBuoyPlugin::Colors_t(CreateColor(1.0, 1.0, 0.0, 1.0), "YELLOW"),
LightBuoyPlugin::Colors_t(CreateColor(0.0, 0.0, 0.0, 1.0), "OFF")}

List of the color options (red, green, blue, yellow and no color) with their string name for logging.

Definition at line 118 of file light_buoy_plugin.hh.

std::mutex LightBuoyPlugin::mutex
private

Locks state and pattern member variables.

Definition at line 158 of file light_buoy_plugin.hh.

ros::NodeHandle LightBuoyPlugin::nh
private

ROS Node handle.

Definition at line 133 of file light_buoy_plugin.hh.

std::string LightBuoyPlugin::ns
private

ROS namespace.

Definition at line 143 of file light_buoy_plugin.hh.

Pattern_t LightBuoyPlugin::pattern
private

The color pattern.

Definition at line 136 of file light_buoy_plugin.hh.

gazebo::rendering::ScenePtr LightBuoyPlugin::scene
private

Pointer to the scene node.

Definition at line 149 of file light_buoy_plugin.hh.

bool LightBuoyPlugin::shuffleEnabled = true
private

Whether shuffle is enabled via a ROS topic or not.

Definition at line 127 of file light_buoy_plugin.hh.

uint8_t LightBuoyPlugin::state = 0u
private

Track current index in pattern.

See also
IncrementState(const ros::TimerEvent &_event)

Definition at line 140 of file light_buoy_plugin.hh.

gazebo::common::Timer LightBuoyPlugin::timer
private

Timer used to switch colors every second.

Definition at line 155 of file light_buoy_plugin.hh.

std::string LightBuoyPlugin::topic
private

ROS topic.

Definition at line 146 of file light_buoy_plugin.hh.

gazebo::event::ConnectionPtr LightBuoyPlugin::updateConnection
private

Connects to rendering update event.

Definition at line 152 of file light_buoy_plugin.hh.

std::vector<std::string> LightBuoyPlugin::visualNames
private

Collection of visual names.

Definition at line 121 of file light_buoy_plugin.hh.

std::vector<gazebo::rendering::VisualPtr> LightBuoyPlugin::visuals
private

Pointer to the visual elements to modify.

Definition at line 124 of file light_buoy_plugin.hh.


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


vmrc_gazebo
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Sun Feb 17 2019 03:14:16