Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
SymbolController Class Reference

Controls the shape and color of a symbol. More...

#include <symbol_controller.hh>

Inheritance diagram for SymbolController:
Inheritance graph
[legend]

Public Member Functions

virtual void Load (gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf)
 
void Shuffle ()
 Create a new combination of shape/color. More...
 
 SymbolController ()=default
 Constructor. More...
 

Private Member Functions

void Publish (const ros::TimerEvent &_event)
 Publish the current shape/color combination. This callback is used for publishing the current combination after some time to make sure that all subscribers are up and runnig. More...
 
void Publish ()
 Publish the current shape/color combination. More...
 
bool Shuffle (std_srvs::Trigger::Request &_req, std_srvs::Trigger::Response &_res)
 ROS service callback for creating a new shape/color combination. More...
 
void ShuffleColor ()
 Choose a new random color. More...
 
void ShuffleShape ()
 Choose a new random shape. More...
 

Private Attributes

ros::ServiceServer changePatternServer
 Service to generate a new random shape/color. More...
 
std::string color
 The current color. More...
 
ros::NodeHandle nh
 Node handle. More...
 
std::string shape
 The current shape. More...
 
std::vector< ros::PublishersymbolPubs
 Publisher to set the color to each of the 3 potential shapes. More...
 
ros::Timer timer
 Timer triggered in simulated time to update the shape/color for. 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...
 

Detailed Description

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:

<robotNamespace> ROS namespace of Node, can be used to have multiple plugins. <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.

Definition at line 43 of file symbol_controller.hh.

Constructor & Destructor Documentation

SymbolController::SymbolController ( )
default

Constructor.

Member Function Documentation

void SymbolController::Load ( gazebo::physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)
virtual

Definition at line 53 of file symbol_controller.cc.

void SymbolController::Publish ( const ros::TimerEvent _event)
private

Publish the current shape/color combination. This callback is used for publishing the current combination after some time to make sure that all subscribers are up and runnig.

Parameters
[in]_eventUnused.

Definition at line 187 of file symbol_controller.cc.

void SymbolController::Publish ( )
private

Publish the current shape/color combination.

Definition at line 193 of file symbol_controller.cc.

void SymbolController::Shuffle ( )

Create a new combination of shape/color.

Definition at line 150 of file symbol_controller.cc.

bool SymbolController::Shuffle ( std_srvs::Trigger::Request &  _req,
std_srvs::Trigger::Response &  _res 
)
private

ROS service callback for creating a new shape/color combination.

Parameters
[in]_reqUnused.
[out]_resService result.
Returns
True on success or false otherwise.

Definition at line 141 of file symbol_controller.cc.

void SymbolController::ShuffleColor ( )
private

Choose a new random color.

Definition at line 172 of file symbol_controller.cc.

void SymbolController::ShuffleShape ( )
private

Choose a new random shape.

Definition at line 158 of file symbol_controller.cc.

Member Data Documentation

ros::ServiceServer SymbolController::changePatternServer
private

Service to generate a new random shape/color.

Definition at line 95 of file symbol_controller.hh.

std::string SymbolController::color
private

The current color.

Definition at line 86 of file symbol_controller.hh.

std::map< std::string, std_msgs::ColorRGBA > SymbolController::kColors
staticprivate
Initial value:
=
{
{"red", createColor(1.0, 0.0, 0.0, 1.0)},
{"green", createColor(0.0, 1.0, 0.0, 1.0)},
{"blue", createColor(0.0, 0.0, 1.0, 1.0)},
}

List of the color options (red, green, blue, and no color) with their string name for logging.

Definition at line 79 of file symbol_controller.hh.

std::vector< std::string > SymbolController::kShapes
staticprivate
Initial value:
=
{"circle", "cross", "triangle"}

List of the shape options (circle, cross, triangle) with their string name for logging.

Definition at line 83 of file symbol_controller.hh.

ros::NodeHandle SymbolController::nh
private

Node handle.

Definition at line 98 of file symbol_controller.hh.

std::string SymbolController::shape
private

The current shape.

Definition at line 89 of file symbol_controller.hh.

std::vector<ros::Publisher> SymbolController::symbolPubs
private

Publisher to set the color to each of the 3 potential shapes.

Definition at line 92 of file symbol_controller.hh.

ros::Timer SymbolController::timer
private

Timer triggered in simulated time to update the shape/color for.

Definition at line 102 of file symbol_controller.hh.


The documentation for this class was generated from the following files:


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