18 #ifndef VRX_GAZEBO_PLACARD_PLUGIN_HH_ 19 #define VRX_GAZEBO_PLACARD_PLUGIN_HH_ 22 #include <std_msgs/ColorRGBA.h> 23 #include <std_msgs/Empty.h> 24 #include <dock_placard.pb.h> 31 #include <gazebo/gazebo.hh> 37 const dock_placard_msgs::msgs::DockPlacard>
79 public:
void Load(gazebo::rendering::VisualPtr _parent,
80 sdf::ElementPtr _sdf);
88 private:
static std_msgs::ColorRGBA CreateColor(
const double _r,
94 private:
void InitializeAllPatterns();
98 private:
bool ParseSDF(sdf::ElementPtr _sdf);
101 private:
void Update();
105 private:
void ChangeSymbol(
const std_msgs::Empty::ConstPtr &_msg);
113 private:
static std::map<std::string, std_msgs::ColorRGBA>
kColors;
117 private:
static std::vector<std::string>
kShapes;
129 private:
size_t allPatternsIdx = 0u;
135 private: std::vector<gazebo::rendering::VisualPtr>
visuals;
138 private:
bool shuffleEnabled =
true;
147 private: std::string
ns;
153 private: gazebo::transport::NodePtr
gzNode;
162 private: gazebo::rendering::ScenePtr
scene;
static std::vector< std::string > kShapes
List of the shape options (circle, cross, triangle) with their string name for logging.
ros::NodeHandle nh
ROS Node handle.
gazebo::rendering::ScenePtr scene
Pointer to the scene node.
gazebo::event::ConnectionPtr updateConnection
Connects to rendering update event.
std::mutex mutex
Locks state and pattern member variables.
ros::Subscriber changeSymbolSub
Service to generate and display a new symbol.
std::string rosShuffleTopic
ROS topic.
gazebo::transport::NodePtr gzNode
gazebo Node
gazebo::common::Time nextUpdateTime
Next time where the plugin should be updated.
std::string color
The current color.
Controls the shape and color of a symbol.
std::vector< std::array< std::string, 2u > > allPatterns
All color/symbol sequences.
std::vector< std::string > visualNames
Collection of visual names.
const boost::shared_ptr< const dock_placard_msgs::msgs::DockPlacard > ConstDockPlacardPtr
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...
std::string ns
ROS namespace.
std::string symbolSubTopic
gazebo symbol sub topic
std::vector< gazebo::rendering::VisualPtr > visuals
Pointer to the visual elements to modify.
std::string shape
The current shape.
gazebo::transport::SubscriberPtr symbolSub
symbol subscriber