Controls the shape and color of a symbol. More...
#include <placard_plugin.hh>
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... | |
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.
PlacardPlugin::PlacardPlugin | ( | ) |
Definition at line 33 of file placard_plugin.cc.
|
private |
ROS callback for changing a symbol and its color.
[in] | _msg | Not used. |
Definition at line 252 of file placard_plugin.cc.
|
private |
Gazebo callback for changing light to a specific color pattern.
[in] | _msg | New symbol. |
Definition at line 96 of file placard_plugin.cc.
|
staticprivate |
Creates a std_msgs::ColorRGBA message from 4 doubles.
[in] | _r | Red. |
[in] | _g | Green. |
[in] | _b | Blue. |
[in] | _a | Alpha. |
Definition at line 39 of file placard_plugin.cc.
|
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.
|
private |
Parse all SDF parameters.
[in] | _sdf | SDF elements. |
Definition at line 105 of file placard_plugin.cc.
|
private |
Display the symbol in the placard.
Definition at line 200 of file placard_plugin.cc.
|
private |
All color/symbol sequences.
Definition at line 126 of file placard_plugin.hh.
|
private |
The index pointing to one of the potential color/symbol sequence.
Definition at line 129 of file placard_plugin.hh.
|
private |
Service to generate and display a new symbol.
Definition at line 141 of file placard_plugin.hh.
|
private |
The current color.
Definition at line 120 of file placard_plugin.hh.
|
private |
gazebo Node
Definition at line 153 of file placard_plugin.hh.
|
staticprivate |
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.
|
staticprivate |
List of the shape options (circle, cross, triangle) with their string name for logging.
Definition at line 117 of file placard_plugin.hh.
|
private |
Locks state and pattern member variables.
Definition at line 171 of file placard_plugin.hh.
|
private |
Next time where the plugin should be updated.
Definition at line 168 of file placard_plugin.hh.
|
private |
ROS Node handle.
Definition at line 144 of file placard_plugin.hh.
|
private |
ROS namespace.
Definition at line 147 of file placard_plugin.hh.
|
private |
ROS topic.
Definition at line 150 of file placard_plugin.hh.
|
private |
Pointer to the scene node.
Definition at line 162 of file placard_plugin.hh.
|
private |
The current shape.
Definition at line 123 of file placard_plugin.hh.
|
private |
Whether shuffle is enabled via a ROS topic or not.
Definition at line 138 of file placard_plugin.hh.
|
private |
symbol subscriber
Definition at line 159 of file placard_plugin.hh.
|
private |
gazebo symbol sub topic
Definition at line 156 of file placard_plugin.hh.
|
private |
Connects to rendering update event.
Definition at line 165 of file placard_plugin.hh.
|
private |
Collection of visual names.
Definition at line 132 of file placard_plugin.hh.
|
private |
Pointer to the visual elements to modify.
Definition at line 135 of file placard_plugin.hh.