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

 LightBuoyPlugin ()
 
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, 5 >
 

Private Member Functions

void ChangePattern (const std_msgs::Empty::ConstPtr &_msg)
 ROS callback for generating a new color pattern. More...
 
void ChangePatternTo (gazebo::ConstLightBuoyColorsPtr &_msg)
 Gazebo callback for changing light to a specific color pattern. More...
 
void InitializeAllPatterns ()
 Initialize all color sequences. 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

std::vector< Pattern_tallPatterns
 All color sequences. More...
 
size_t allPatternsIdx = 0u
 The index pointing to one of the potential color sequences. More...
 
ros::Subscriber changePatternSub
 Subscriber to generate and display a new color sequence. More...
 
gazebo::transport::SubscriberPtr colorSub
 
std::string gzColorsTopic
 gazebo topic. More...
 
gazebo::transport::NodePtr gzNode
 
std::mutex mutex
 Locks state and pattern member variables. More...
 
gazebo::common::Time nextUpdateTime
 Next time where the plugin should be updated. More...
 
ros::NodeHandle nh
 ROS Node handle. More...
 
std::string ns
 ROS namespace. More...
 
Pattern_t pattern
 The color pattern. More...
 
std::string rosShuffleTopic
 ROS topic. 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::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. <ros_shuffle_topic>: The ROS topic used to request color changes. <gz_colors_topic>: The gazebo topic used to request specific 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>vrx</robot_namespace> <ros_shuffle_topic>light_buoy/shuffle</ros_shuffle_topic> </plugin>

Definition at line 73 of file light_buoy_plugin.hh.

Member Typedef Documentation

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

Definition at line 118 of file light_buoy_plugin.hh.

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

Definition at line 123 of file light_buoy_plugin.hh.

Constructor & Destructor Documentation

LightBuoyPlugin::LightBuoyPlugin ( )

Definition at line 80 of file light_buoy_plugin.cc.

Member Function Documentation

void LightBuoyPlugin::ChangePattern ( const std_msgs::Empty::ConstPtr &  _msg)
private

ROS callback for generating a new color pattern.

Parameters
[in]_msgNot used.

Definition at line 271 of file light_buoy_plugin.cc.

void LightBuoyPlugin::ChangePatternTo ( gazebo::ConstLightBuoyColorsPtr _msg)
private

Gazebo callback for changing light to a specific color pattern.

Parameters
[in]_msgNew color sequence.

Definition at line 86 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::InitializeAllPatterns ( )
private

Initialize all color sequences.

Definition at line 57 of file light_buoy_plugin.cc.

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

Definition at line 104 of file light_buoy_plugin.cc.

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

Parse all SDF parameters.

Parameters
[in]_sdfSDF elements.

Definition at line 143 of file light_buoy_plugin.cc.

void LightBuoyPlugin::Update ( )
private

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

Definition at line 227 of file light_buoy_plugin.cc.

Member Data Documentation

std::vector<Pattern_t> LightBuoyPlugin::allPatterns
private

All color sequences.

Definition at line 130 of file light_buoy_plugin.hh.

size_t LightBuoyPlugin::allPatternsIdx = 0u
private

The index pointing to one of the potential color sequences.

Definition at line 133 of file light_buoy_plugin.hh.

ros::Subscriber LightBuoyPlugin::changePatternSub
private

Subscriber to generate and display a new color sequence.

Definition at line 145 of file light_buoy_plugin.hh.

gazebo::transport::SubscriberPtr LightBuoyPlugin::colorSub
private

Definition at line 154 of file light_buoy_plugin.hh.

std::string LightBuoyPlugin::gzColorsTopic
private

gazebo topic.

Definition at line 169 of file light_buoy_plugin.hh.

gazebo::transport::NodePtr LightBuoyPlugin::gzNode
private

Definition at line 151 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 127 of file light_buoy_plugin.hh.

std::mutex LightBuoyPlugin::mutex
private

Locks state and pattern member variables.

Definition at line 181 of file light_buoy_plugin.hh.

gazebo::common::Time LightBuoyPlugin::nextUpdateTime
private

Next time where the plugin should be updated.

Definition at line 178 of file light_buoy_plugin.hh.

ros::NodeHandle LightBuoyPlugin::nh
private

ROS Node handle.

Definition at line 148 of file light_buoy_plugin.hh.

std::string LightBuoyPlugin::ns
private

ROS namespace.

Definition at line 163 of file light_buoy_plugin.hh.

Pattern_t LightBuoyPlugin::pattern
private

The color pattern.

Definition at line 157 of file light_buoy_plugin.hh.

std::string LightBuoyPlugin::rosShuffleTopic
private

ROS topic.

Definition at line 166 of file light_buoy_plugin.hh.

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

Pointer to the scene node.

Definition at line 172 of file light_buoy_plugin.hh.

bool LightBuoyPlugin::shuffleEnabled = true
private

Whether shuffle is enabled via a ROS topic or not.

Definition at line 142 of file light_buoy_plugin.hh.

uint8_t LightBuoyPlugin::state = 0u
private

Track current index in pattern.

Definition at line 160 of file light_buoy_plugin.hh.

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

Connects to rendering update event.

Definition at line 175 of file light_buoy_plugin.hh.

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

Collection of visual names.

Definition at line 136 of file light_buoy_plugin.hh.

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

Pointer to the visual elements to modify.

Definition at line 139 of file light_buoy_plugin.hh.


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


vrx_gazebo
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Thu May 7 2020 03:54:56