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

Controls the shape and color of a symbol. More...

#include <placard_plugin.hh>

Inheritance diagram for PlacardPlugin:
Inheritance graph
[legend]

Public Member Functions

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

Private Member Functions

void ChangeSymbol (const std_msgs::Empty::ConstPtr &_msg)
 ROS callback for changing a symbol and its color. More...
 
void ChangeSymbolTo (gazebo::ConstDockPlacardPtr &_msg)
 Gazebo callback for changing light to a specific color pattern. More...
 
void InitializeAllPatterns ()
 Initialize all color/symbol sequences. More...
 
bool ParseSDF (sdf::ElementPtr _sdf)
 Parse all SDF parameters. More...
 
void Update ()
 Display the symbol in the placard. 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...
 

Private Attributes

std::vector< std::array< std::string, 2u > > allPatterns
 All color/symbol sequences. More...
 
size_t allPatternsIdx = 0u
 The index pointing to one of the potential color/symbol sequence. More...
 
ros::Subscriber changeSymbolSub
 Service to generate and display a new symbol. More...
 
std::string color
 The current color. More...
 
gazebo::transport::NodePtr gzNode
 gazebo Node More...
 
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...
 
std::string rosShuffleTopic
 ROS topic. More...
 
gazebo::rendering::ScenePtr scene
 Pointer to the scene node. More...
 
std::string shape
 The current shape. More...
 
bool shuffleEnabled = true
 Whether shuffle is enabled via a ROS topic or not. More...
 
gazebo::transport::SubscriberPtr symbolSub
 symbol subscriber More...
 
std::string symbolSubTopic
 gazebo symbol sub 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 std::map< std::string, std_msgs::ColorRGBA > kColors
 List of the color options (red, green, blue, and no color) with their string name for logging. More...
 
static std::vector< std::string > kShapes
 List of the shape options (circle, cross, triangle) with their string name for logging. More...
 

Detailed Description

Controls the shape and color of a symbol.

It selects a shape (triangle, cross, circle) and a color (red, green, blue) and applies to the current symbol This plugin can be configured with the following SDF tags:

<shape> "triangle", "cross" or "circle". If ommited, the shape will be randomly selected. <color> "red", "green" or "blue". If ommited, the color will be randomly selected. <shuffle>: True if the topic for shuffling the sequence is enabled. <robot_namespace> ROS namespace of Node, can be used to have multiple plugins. <ros_shuffle_topic>: The ROS topic used to request color changes. <gz_symbol_topic>: The gazebo topic subscribed to set symbol changes defaults to /<robot_namespace>/symbol <visuals>: The set of visual symbols. It contains at least one visual: <visual>: A visual displaying a shape.

Here's an example: <plugin name="placard1plugin" filename="libplacard_plugin.so"> <shape>triangle</shape> <color>red</color> <visuals> <visual>dock_2018_placard1::visual_circle</visual> <visual>dock_2018_placard1::visual_h_cross</visual> <visual>dock_2018_placard1::visual_v_cross</visual> <visual>dock_2018_placard1::visual_triangle</visual> </visuals> <shuffle>true</shuffle> <robot_namespace>vrx</robot_namespace> <topic>dock/placard/shuffle</topic> </plugin>

Definition at line 74 of file placard_plugin.hh.

Constructor & Destructor Documentation

PlacardPlugin::PlacardPlugin ( )

Definition at line 33 of file placard_plugin.cc.

Member Function Documentation

void PlacardPlugin::ChangeSymbol ( const std_msgs::Empty::ConstPtr &  _msg)
private

ROS callback for changing a symbol and its color.

Parameters
[in]_msgNot used.

Definition at line 252 of file placard_plugin.cc.

void PlacardPlugin::ChangeSymbolTo ( gazebo::ConstDockPlacardPtr _msg)
private

Gazebo callback for changing light to a specific color pattern.

Parameters
[in]_msgNew symbol.

Definition at line 96 of file placard_plugin.cc.

std_msgs::ColorRGBA PlacardPlugin::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 39 of file placard_plugin.cc.

void PlacardPlugin::InitializeAllPatterns ( )
private

Initialize all color/symbol sequences.

Definition at line 51 of file placard_plugin.cc.

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

Definition at line 59 of file placard_plugin.cc.

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

Parse all SDF parameters.

Parameters
[in]_sdfSDF elements.

Definition at line 105 of file placard_plugin.cc.

void PlacardPlugin::Update ( )
private

Display the symbol in the placard.

Definition at line 200 of file placard_plugin.cc.

Member Data Documentation

std::vector<std::array<std::string, 2u> > PlacardPlugin::allPatterns
private

All color/symbol sequences.

Definition at line 126 of file placard_plugin.hh.

size_t PlacardPlugin::allPatternsIdx = 0u
private

The index pointing to one of the potential color/symbol sequence.

Definition at line 129 of file placard_plugin.hh.

ros::Subscriber PlacardPlugin::changeSymbolSub
private

Service to generate and display a new symbol.

Definition at line 141 of file placard_plugin.hh.

std::string PlacardPlugin::color
private

The current color.

Definition at line 120 of file placard_plugin.hh.

gazebo::transport::NodePtr PlacardPlugin::gzNode
private

gazebo Node

Definition at line 153 of file placard_plugin.hh.

std::map< std::string, std_msgs::ColorRGBA > PlacardPlugin::kColors
staticprivate
Initial value:
=
{
{"red", CreateColor(1.0, 0.0, 0.0, 1.0)},
{"green", CreateColor(0.0, 1.0, 0.0, 1.0)},
{"blue", CreateColor(0.0, 0.0, 1.0, 1.0)},
}

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

Definition at line 113 of file placard_plugin.hh.

std::vector< std::string > PlacardPlugin::kShapes
staticprivate
Initial value:
=
{"circle", "cross", "triangle"}

List of the shape options (circle, cross, triangle) with their string name for logging.

Definition at line 117 of file placard_plugin.hh.

std::mutex PlacardPlugin::mutex
private

Locks state and pattern member variables.

Definition at line 171 of file placard_plugin.hh.

gazebo::common::Time PlacardPlugin::nextUpdateTime
private

Next time where the plugin should be updated.

Definition at line 168 of file placard_plugin.hh.

ros::NodeHandle PlacardPlugin::nh
private

ROS Node handle.

Definition at line 144 of file placard_plugin.hh.

std::string PlacardPlugin::ns
private

ROS namespace.

Definition at line 147 of file placard_plugin.hh.

std::string PlacardPlugin::rosShuffleTopic
private

ROS topic.

Definition at line 150 of file placard_plugin.hh.

gazebo::rendering::ScenePtr PlacardPlugin::scene
private

Pointer to the scene node.

Definition at line 162 of file placard_plugin.hh.

std::string PlacardPlugin::shape
private

The current shape.

Definition at line 123 of file placard_plugin.hh.

bool PlacardPlugin::shuffleEnabled = true
private

Whether shuffle is enabled via a ROS topic or not.

Definition at line 138 of file placard_plugin.hh.

gazebo::transport::SubscriberPtr PlacardPlugin::symbolSub
private

symbol subscriber

Definition at line 159 of file placard_plugin.hh.

std::string PlacardPlugin::symbolSubTopic
private

gazebo symbol sub topic

Definition at line 156 of file placard_plugin.hh.

gazebo::event::ConnectionPtr PlacardPlugin::updateConnection
private

Connects to rendering update event.

Definition at line 165 of file placard_plugin.hh.

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

Collection of visual names.

Definition at line 132 of file placard_plugin.hh.

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

Pointer to the visual elements to modify.

Definition at line 135 of file placard_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