18 #ifndef VRX_GAZEBO_LIGHT_BUOY_PLUGIN_HH_ 19 #define VRX_GAZEBO_LIGHT_BUOY_PLUGIN_HH_ 22 #include <std_msgs/ColorRGBA.h> 23 #include <std_msgs/Empty.h> 24 #include <light_buoy_colors.pb.h> 31 #include <gazebo/gazebo.hh> 37 const light_buoy_colors_msgs::msgs::LightBuoyColors>
79 public:
void Load(gazebo::rendering::VisualPtr _parent,
80 sdf::ElementPtr _sdf);
88 private:
static std_msgs::ColorRGBA CreateColor(
const double _r,
96 private:
static uint8_t IndexFromColor(
const std::string &_color);
99 private:
void InitializeAllPatterns();
103 private:
bool ParseSDF(sdf::ElementPtr _sdf);
107 private:
void ChangePattern(
const std_msgs::Empty::ConstPtr &_msg);
114 private:
void Update();
118 private:
using Colors_t = std::pair<std_msgs::ColorRGBA, std::string>;
127 private:
static const std::array<Colors_t, 5>
kColors;
133 private:
size_t allPatternsIdx = 0u;
139 private: std::vector<gazebo::rendering::VisualPtr>
visuals;
142 private:
bool shuffleEnabled =
true;
151 private: gazebo::transport::NodePtr
gzNode;
154 private: gazebo::transport::SubscriberPtr
colorSub;
160 private: uint8_t state = 0u;
163 private: std::string
ns;
172 private: gazebo::rendering::ScenePtr
scene;
std::vector< gazebo::rendering::VisualPtr > visuals
Pointer to the visual elements to modify.
gazebo::transport::SubscriberPtr colorSub
Visual plugin for changing the color of some visual elements using ROS messages. This plugin accepts ...
std::string rosShuffleTopic
ROS topic.
std::vector< std::string > visualNames
Collection of visual names.
ros::NodeHandle nh
ROS Node handle.
std::string ns
ROS namespace.
std::pair< std_msgs::ColorRGBA, std::string > Colors_t
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...
Pattern_t pattern
The color pattern.
gazebo::transport::NodePtr gzNode
std::string gzColorsTopic
gazebo topic.
gazebo::rendering::ScenePtr scene
Pointer to the scene node.
std::mutex mutex
Locks state and pattern member variables.
gazebo::event::ConnectionPtr updateConnection
Connects to rendering update event.
std::vector< Pattern_t > allPatterns
All color sequences.
std::array< uint8_t, 5 > Pattern_t
ros::Subscriber changePatternSub
Subscriber to generate and display a new color sequence.
gazebo::common::Time nextUpdateTime
Next time where the plugin should be updated.
const boost::shared_ptr< const light_buoy_colors_msgs::msgs::LightBuoyColors > ConstLightBuoyColorsPtr