light_buoy_plugin.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2019 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef VRX_GAZEBO_LIGHT_BUOY_PLUGIN_HH_
19 #define VRX_GAZEBO_LIGHT_BUOY_PLUGIN_HH_
20 
21 #include <ros/ros.h>
22 #include <std_msgs/ColorRGBA.h>
23 #include <std_msgs/Empty.h>
24 #include <light_buoy_colors.pb.h>
25 #include <array>
26 #include <cstdint>
27 #include <mutex>
28 #include <string>
29 #include <utility>
30 #include <vector>
31 #include <gazebo/gazebo.hh>
32 #include <sdf/sdf.hh>
33 
34 namespace gazebo
35 {
36  typedef const boost::shared_ptr<
37  const light_buoy_colors_msgs::msgs::LightBuoyColors>
39 }
40 
55 // defaults to /vrx/light_buoy/new_pattern
73 class LightBuoyPlugin : public gazebo::VisualPlugin
74 {
75  // \brief Constructor
76  public: LightBuoyPlugin();
77 
78  // Documentation inherited.
79  public: void Load(gazebo::rendering::VisualPtr _parent,
80  sdf::ElementPtr _sdf);
81 
88  private: static std_msgs::ColorRGBA CreateColor(const double _r,
89  const double _g,
90  const double _b,
91  const double _a);
92 
96  private: static uint8_t IndexFromColor(const std::string &_color);
97 
99  private: void InitializeAllPatterns();
100 
103  private: bool ParseSDF(sdf::ElementPtr _sdf);
104 
107  private: void ChangePattern(const std_msgs::Empty::ConstPtr &_msg);
108 
111  private: void ChangePatternTo(gazebo::ConstLightBuoyColorsPtr &_msg);
112 
114  private: void Update();
115 
118  private: using Colors_t = std::pair<std_msgs::ColorRGBA, std::string>;
119 
123  private: using Pattern_t = std::array<uint8_t, 5>;
124 
127  private: static const std::array<Colors_t, 5> kColors;
128 
130  private: std::vector<Pattern_t> allPatterns;
131 
133  private: size_t allPatternsIdx = 0u;
134 
136  private: std::vector<std::string> visualNames;
137 
139  private: std::vector<gazebo::rendering::VisualPtr> visuals;
140 
142  private: bool shuffleEnabled = true;
143 
146 
148  private: ros::NodeHandle nh;
149 
150  // \brief Gazebo Node
151  private: gazebo::transport::NodePtr gzNode;
152 
153  // \brief Gazebo subscriber listening for color specification
154  private: gazebo::transport::SubscriberPtr colorSub;
155 
157  private: Pattern_t pattern;
158 
160  private: uint8_t state = 0u;
161 
163  private: std::string ns;
164 
166  private: std::string rosShuffleTopic;
167 
169  private: std::string gzColorsTopic;
170 
172  private: gazebo::rendering::ScenePtr scene;
173 
175  private: gazebo::event::ConnectionPtr updateConnection;
176 
178  private: gazebo::common::Time nextUpdateTime;
179 
181  private: std::mutex mutex;
182 };
183 
184 #endif
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


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