00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "wviz_scene_manager/wviz_scene_manager.h"
00037 #include <wviz_scene_manager/VisualizationScene.h>
00038
00039 namespace wviz_scene_manager {
00040
00041 Scene::Scene() : is_dirty_(false)
00042 {
00043 }
00044
00045 SceneManager::SceneManager(ros::NodeHandle& node) :
00046 node_(node)
00047 {
00048 ros::NodeHandle private_node("~");
00049
00050 scene_pub_ = node_.advertise<wviz_scene_manager::VisualizationScene>("scene", 5);
00051 add_marker_srv_ = private_node.advertiseService("add_marker", &SceneManager::addMarker, this);
00052 remove_marker_srv_ = private_node.advertiseService("remove_marker", &SceneManager::removeMarker, this);
00053 }
00054
00055 SceneManager::~SceneManager()
00056 {
00057 }
00058
00059 void SceneManager::visualizationMarkerCallback(const visualization_msgs::MarkerConstPtr& marker)
00060 {
00061 boost::unique_lock<boost::mutex> lock(scene_.mutex_);
00062 std::string marker_id = getMarkerStringID(*marker);
00063 int marker_action = marker->action;
00064
00065 if (marker_action == visualization_msgs::Marker::DELETE) {
00066 ROS_INFO("Deleting marker with id %s", marker_id.c_str());
00067 scene_.visualization_markers_.erase(marker_id);
00068 }
00069 else if (marker_action == visualization_msgs::Marker::ADD ||
00070 marker_action == visualization_msgs::Marker::MODIFY ) {
00071 ROS_INFO("Adding marker with id %s", marker_id.c_str());
00072 scene_.visualization_markers_.erase(marker_id);
00073 scene_.visualization_markers_.insert(std::make_pair(marker_id,*marker));
00074 }
00075 scene_.is_dirty_ = true;
00076 }
00077
00078 bool SceneManager::addMarker(wviz_scene_manager::AddMarker::Request& req, wviz_scene_manager::AddMarker::Response& resp)
00079 {
00080 std::string topic = req.topic;
00081 ROS_INFO("Adding subscriber for %s", topic.c_str());
00082 visualization_marker_subscribers_[topic] = node_.subscribe(topic, 10, &SceneManager::visualizationMarkerCallback, this);
00083 return true;
00084 }
00085
00086 bool SceneManager::removeMarker(wviz_scene_manager::RemoveMarker::Request& req, wviz_scene_manager::RemoveMarker::Response& resp)
00087 {
00088 std::string topic = req.topic;
00089 ROS_INFO("Removing subscriber for %s", topic.c_str());
00090 visualization_marker_subscribers_.erase(topic);
00091 return true;
00092 }
00093
00094 void SceneManager::spin()
00095 {
00096 ros::Rate r(10);
00097 while (node_.ok())
00098 {
00099 scene_.mutex_.lock();
00100
00101
00102 if(scene_.is_dirty_) {
00103 VisualizationScene scene_msg;
00104 std::map<std::string,visualization_msgs::Marker>::iterator it = scene_.visualization_markers_.begin();
00105 for(;it!=scene_.visualization_markers_.end();it++) {
00106 scene_msg.markers.push_back(it->second);
00107 }
00108 ROS_INFO("Sending a scene with %d markers.", (int)scene_.visualization_markers_.size());
00109 scene_pub_.publish(scene_msg);
00110 scene_.is_dirty_ = false;
00111 }
00112
00113 scene_.mutex_.unlock();
00114 ros::spinOnce();
00115 r.sleep();
00116 }
00117 }
00118
00119 std::string SceneManager::getMarkerStringID(const visualization_msgs::Marker& marker)
00120 {
00121 std::stringstream ss;
00122 ss << marker.ns << "/" << marker.id;
00123 return ss.str();
00124 }
00125
00126 }
00127
00128 int main(int argc, char** argv)
00129 {
00130 ros::init(argc, argv, "wviz_scene_manager");
00131
00132 ros::NodeHandle nh;
00133 wviz_scene_manager::SceneManager manager(nh);
00134 manager.spin();
00135
00136 return(0);
00137 }
00138
00139