#include <marker_manager.hpp>
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_ |
Maintains a set of common resources for filling in a MarkerArray msg
Definition at line 21 of file marker_manager.hpp.
Definition at line 5 of file marker_manager.cpp.
Definition at line 7 of file marker_manager.cpp.
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.
group_key | The marker group key. |
marker_name | Name for indexing purposes. |
ns | the namespace of the new marker. |
frame_id | The frame on which the marker is expressed. |
type | The marker type. |
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.
group_key | The new marker group key. |
topic_name | The topic name under which the marker group will be published. |
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
group_key | The marker group key. |
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.
group_key | The marker group key. |
marker_name | Name for indexing purposes. |
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.
group_key | The marker group key. |
marker_name | Name for indexing purposes. |
initial_point | Initial point of the marker |
final_point | Initial point of the marker |
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.
group_key | The marker group key. |
marker_name | Name for indexing purposes. |
pose | The marker 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.
group_key | The marker group key. |
marker_name | Name for indexing purposes. |
Definition at line 111 of file marker_manager.cpp.
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.