Public Member Functions | Private Member Functions | Private Attributes
generic_control_toolbox::MarkerManager Class Reference

#include <marker_manager.hpp>

Inheritance diagram for generic_control_toolbox::MarkerManager:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool addMarker (const std::string &group_key, const std::string &marker_name, const std::string &ns, const std::string &frame_id, MarkerType type)
bool addMarkerGroup (const std::string &group_key, const std::string &topic_name)
 MarkerManager ()
void publishMarkers ()
bool setMarkerColor (const std::string &group_key, const std::string &marker_name, double r, double g, double b)
bool setMarkerPoints (const std::string &group_key, const std::string &marker_name, const Eigen::Vector3d &initial_point, const Eigen::Vector3d &final_point)
bool setMarkerPose (const std::string &group_key, const std::string &marker_name, const Eigen::Affine3d &pose)
bool setMarkerScale (const std::string &group_key, const std::string &marker_name, double x, double y, double z)
 ~MarkerManager ()

Private Member Functions

bool getMarkerId (const std::string &group_key, const std::string &marker_name, int &id) const

Private Attributes

std::map< std::string,
visualization_msgs::MarkerArray > 
marker_array_
std::map< std::string,
std::map< std::string, int > > 
marker_map_
std::map< std::string,
std::shared_ptr
< realtime_tools::RealtimePublisher
< visualization_msgs::MarkerArray > > > 
marker_pub_
ros::NodeHandle n_

Detailed Description

Maintains a set of common resources for filling in a MarkerArray msg

Definition at line 21 of file marker_manager.hpp.


Constructor & Destructor Documentation

Definition at line 5 of file marker_manager.cpp.

Definition at line 7 of file marker_manager.cpp.


Member Function Documentation

bool generic_control_toolbox::MarkerManager::addMarker ( const std::string &  group_key,
const std::string &  marker_name,
const std::string &  ns,
const std::string &  frame_id,
MarkerType  type 
)

Initializes a marker in the marker array with default color and scale.

Parameters:
group_keyThe marker group key.
marker_nameName for indexing purposes.
nsthe namespace of the new marker.
frame_idThe frame on which the marker is expressed.
typeThe marker type.
Returns:
False is marker_name is already added.

Definition at line 31 of file marker_manager.cpp.

bool generic_control_toolbox::MarkerManager::addMarkerGroup ( const std::string &  group_key,
const std::string &  topic_name 
)

Initializes a new marker group, including a new realtime publisher for the group.

Parameters:
group_keyThe new marker group key.
topic_nameThe topic name under which the marker group will be published.
Returns:
False if something goes wrong, true otherwise.

Definition at line 9 of file marker_manager.cpp.

bool generic_control_toolbox::MarkerManager::getMarkerId ( const std::string &  group_key,
const std::string &  marker_name,
int &  id 
) const [private]

Returns the marker id indexed by the marker_name

Parameters:
group_keyThe marker group key.
Returns:
False if marker not found.

Definition at line 188 of file marker_manager.cpp.

Publishes the marker array. RT safe.

Definition at line 176 of file marker_manager.cpp.

bool generic_control_toolbox::MarkerManager::setMarkerColor ( const std::string &  group_key,
const std::string &  marker_name,
double  r,
double  g,
double  b 
)

Sets the indexed marker color.

Parameters:
group_keyThe marker group key.
marker_nameName for indexing purposes.
Returns:
False if marker_name is not found.

Definition at line 90 of file marker_manager.cpp.

bool generic_control_toolbox::MarkerManager::setMarkerPoints ( const std::string &  group_key,
const std::string &  marker_name,
const Eigen::Vector3d &  initial_point,
const Eigen::Vector3d &  final_point 
)

Fills a marker with the given initial and end point. Clears existing points.

Parameters:
group_keyThe marker group key.
marker_nameName for indexing purposes.
initial_pointInitial point of the marker
final_pointInitial point of the marker
Returns:
False if marker_name is not found or if marker type does not allow to set points.

Definition at line 132 of file marker_manager.cpp.

bool generic_control_toolbox::MarkerManager::setMarkerPose ( const std::string &  group_key,
const std::string &  marker_name,
const Eigen::Affine3d &  pose 
)

Fills a marker with the given pose.

Parameters:
group_keyThe marker group key.
marker_nameName for indexing purposes.
poseThe marker pose.
Returns:
False if marker_name is not found or if marker type does not allow to set pose.

Definition at line 157 of file marker_manager.cpp.

bool generic_control_toolbox::MarkerManager::setMarkerScale ( const std::string &  group_key,
const std::string &  marker_name,
double  x,
double  y,
double  z 
)

Sets the marker scale.

Parameters:
group_keyThe marker group key.
marker_nameName for indexing purposes.
Returns:
false if marker_name is not found.

Definition at line 111 of file marker_manager.cpp.


Member Data Documentation

std::map<std::string, visualization_msgs::MarkerArray> generic_control_toolbox::MarkerManager::marker_array_ [private]

Definition at line 111 of file marker_manager.hpp.

std::map<std::string, std::map<std::string, int> > generic_control_toolbox::MarkerManager::marker_map_ [private]

Definition at line 110 of file marker_manager.hpp.

std::map<std::string, std::shared_ptr<realtime_tools::RealtimePublisher< visualization_msgs::MarkerArray> > > generic_control_toolbox::MarkerManager::marker_pub_ [private]

Definition at line 114 of file marker_manager.hpp.

Definition at line 115 of file marker_manager.hpp.


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


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 18:02:57