symbol_controller.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 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 VMRC_GAZEBO_SYMBOL_CONTROLLER_HH_
19 #define VMRC_GAZEBO_SYMBOL_CONTROLLER_HH_
20 
21 #include <ros/ros.h>
22 #include <std_msgs/ColorRGBA.h>
23 #include <std_srvs/Trigger.h>
24 
25 #include <map>
26 #include <string>
27 #include <vector>
28 #include <gazebo/gazebo.hh>
29 #include <sdf/sdf.hh>
30 
43 class SymbolController : public gazebo::ModelPlugin
44 {
46  public: SymbolController() = default;
47 
48  // Documentation inherited.
49  public: virtual void Load(gazebo::physics::ModelPtr _parent,
50  sdf::ElementPtr _sdf);
51 
53  public: void Shuffle();
54 
59  private: bool Shuffle(std_srvs::Trigger::Request &_req,
60  std_srvs::Trigger::Response &_res);
61 
63  private: void ShuffleShape();
64 
66  private: void ShuffleColor();
67 
72  private: void Publish(const ros::TimerEvent &_event);
73 
75  private: void Publish();
76 
79  private: static std::map<std::string, std_msgs::ColorRGBA> kColors;
80 
83  private: static std::vector<std::string> kShapes;
84 
86  private: std::string color;
87 
89  private: std::string shape;
90 
92  private: std::vector<ros::Publisher> symbolPubs;
93 
96 
98  private: ros::NodeHandle nh;
99 
101  // the first time.
102  private: ros::Timer timer;
103 };
104 
105 #endif
std::string color
The current color.
void Shuffle()
Create a new combination of shape/color.
ros::NodeHandle nh
Node handle.
virtual void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf)
std::vector< ros::Publisher > symbolPubs
Publisher to set the color to each of the 3 potential shapes.
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...
void ShuffleColor()
Choose a new random color.
Controls the shape and color of a symbol.
std::string shape
The current shape.
static std::vector< std::string > kShapes
List of the shape options (circle, cross, triangle) with their string name for logging.
SymbolController()=default
Constructor.
ros::Timer timer
Timer triggered in simulated time to update the shape/color for.
ros::ServiceServer changePatternServer
Service to generate a new random shape/color.
void Publish()
Publish the current shape/color combination.
void ShuffleShape()
Choose a new random shape.


vmrc_gazebo
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Sun Feb 17 2019 03:14:16