#include <wviz_scene_manager.h>
Public Member Functions | |
bool | addMarker (wviz_scene_manager::AddMarker::Request &req, wviz_scene_manager::AddMarker::Response &resp) |
adds a marker topic to the scene manager | |
std::string | getMarkerStringID (const visualization_msgs::Marker &marker) |
creates a marker id string from a marker message | |
bool | removeMarker (wviz_scene_manager::RemoveMarker::Request &req, wviz_scene_manager::RemoveMarker::Response &resp) |
removes a marker topic from the scene manager | |
SceneManager (ros::NodeHandle &node) | |
Constructor. | |
void | spin () |
Starts the server and spins. | |
void | visualizationMarkerCallback (const visualization_msgs::MarkerConstPtr &marker) |
Callback for visualization markers. | |
virtual | ~SceneManager () |
Destructor - Cleans up. | |
Private Attributes | |
ros::ServiceServer | add_marker_srv_ |
ros::NodeHandle | node_ |
ros::ServiceServer | remove_marker_srv_ |
Scene | scene_ |
ros::Publisher | scene_pub_ |
std::map< std::string, ros::Subscriber > | visualization_marker_subscribers_ |
Definition at line 63 of file wviz_scene_manager.h.
wviz_scene_manager::SceneManager::SceneManager | ( | ros::NodeHandle & | node | ) |
wviz_scene_manager::SceneManager::~SceneManager | ( | ) | [virtual] |
Destructor - Cleans up.
Definition at line 54 of file wviz_scene_manager.cpp.
bool wviz_scene_manager::SceneManager::addMarker | ( | wviz_scene_manager::AddMarker::Request & | req, | |
wviz_scene_manager::AddMarker::Response & | resp | |||
) |
adds a marker topic to the scene manager
Definition at line 77 of file wviz_scene_manager.cpp.
std::string wviz_scene_manager::SceneManager::getMarkerStringID | ( | const visualization_msgs::Marker & | marker | ) |
creates a marker id string from a marker message
Definition at line 118 of file wviz_scene_manager.cpp.
bool wviz_scene_manager::SceneManager::removeMarker | ( | wviz_scene_manager::RemoveMarker::Request & | req, | |
wviz_scene_manager::RemoveMarker::Response & | resp | |||
) |
removes a marker topic from the scene manager
Definition at line 85 of file wviz_scene_manager.cpp.
void wviz_scene_manager::SceneManager::spin | ( | ) |
Starts the server and spins.
Definition at line 93 of file wviz_scene_manager.cpp.
void wviz_scene_manager::SceneManager::visualizationMarkerCallback | ( | const visualization_msgs::MarkerConstPtr & | marker | ) |
Callback for visualization markers.
Definition at line 58 of file wviz_scene_manager.cpp.
ros::ServiceServer wviz_scene_manager::SceneManager::add_marker_srv_ [private] |
Definition at line 104 of file wviz_scene_manager.h.
ros::NodeHandle wviz_scene_manager::SceneManager::node_ [private] |
Definition at line 101 of file wviz_scene_manager.h.
ros::ServiceServer wviz_scene_manager::SceneManager::remove_marker_srv_ [private] |
Definition at line 105 of file wviz_scene_manager.h.
Definition at line 106 of file wviz_scene_manager.h.
ros::Publisher wviz_scene_manager::SceneManager::scene_pub_ [private] |
Definition at line 103 of file wviz_scene_manager.h.
std::map<std::string,ros::Subscriber> wviz_scene_manager::SceneManager::visualization_marker_subscribers_ [private] |
Definition at line 102 of file wviz_scene_manager.h.