rocon_tf_reconstructor.cpp
Go to the documentation of this file.
00001 #include <rocon_tf_reconstructor/rocon_tf_reconstructor.h>
00002 #include <rocon_tf_reconstructor/utils.h>
00003 #include <concert_msgs/Strings.h>
00004 
00005 namespace rocon {
00006 
00007   RoconTFReconstructor::RoconTFReconstructor()
00008   {
00009     this->nh = ros::NodeHandle("");
00010     init();
00011   }
00012   RoconTFReconstructor::RoconTFReconstructor(ros::NodeHandle& n)
00013   {
00014     this->nh = n;
00015     init();
00016   }
00017 
00018 
00019   RoconTFReconstructor::~RoconTFReconstructor()
00020   {
00021   }
00022 
00023   void RoconTFReconstructor::init()
00024   {
00025     getParams();
00026     setSubscriber();
00027   }
00028 
00029   void RoconTFReconstructor::getParams()
00030   {
00031     this->nh.param<std::string>("concert_client_changes",this->sub_client_list_topic, "/concert/conductor/concert_client_changes");
00032     this->nh.param<std::string>("robotpose_topic",this->sub_robotpose_topic,"robot_pose");
00033     this->nh.param<int>("spin_rate", this->spin_rate_, 10);
00034   }
00035 
00036 
00037   void RoconTFReconstructor::setSubscriber()
00038   {
00039     this->sub_clientlist = this->nh.subscribe(this->sub_client_list_topic,10,&RoconTFReconstructor::processClientLists,this);
00040   }
00041 
00042   void RoconTFReconstructor::processClientLists(const concert_msgs::ConcertClients::ConstPtr msg)
00043   {
00044     int i;
00045     std::string name;
00046     std::vector<std::string> client_names;
00047     // TODO : Optimize synchronization using sorting algorithm
00048 
00049     // register newly joined clients
00050     for(i = 0; i <msg->clients.size(); i ++) {
00051       name = msg->clients[i].name;
00052       client_names.push_back(name);
00053 
00054       // if it doesn't exist create subscriber
00055       if(this->sub_clients_pose.find(name) == this->sub_clients_pose.end())
00056       {
00057         std::string topic_name = "/" + name + "/" + this->sub_robotpose_topic;  
00058         topic_name = get_ros_friendly_name(topic_name);
00059         ROS_INFO_STREAM("Create Subscriber for : " << name << "\tTopic : " << topic_name);
00060         this->sub_clients_pose[name] = new RoconPoseClient(this->nh,name,this->sub_robotpose_topic);
00061       }
00062     }
00063 
00064     // remove newly left clients
00065     std::map<std::string,RoconPoseClient*>::iterator iter;
00066     for(iter = this->sub_clients_pose.begin(); iter != this->sub_clients_pose.end(); ++iter)
00067     {
00068       std::string key = iter->first;
00069 
00070       // it does not exist in msg client name array. so this client has left concert.
00071       if(std::find(client_names.begin(),client_names.end(),key) == client_names.end())
00072       {
00073         ROS_INFO_STREAM("Remove subscriber of : " << key);
00074         this->sub_clients_pose.erase(key);
00075       }
00076     }
00077   }
00078 
00079   void RoconTFReconstructor::publishClientTF(std::string client_name,geometry_msgs::PoseStamped pose_stamped)
00080   {
00081     geometry_msgs::TransformStamped odom_tf;
00082 
00083     odom_tf.header = pose_stamped.header;
00084     odom_tf.header.stamp = ros::Time::now();
00085     odom_tf.child_frame_id = client_name;
00086     odom_tf.transform.translation.x = pose_stamped.pose.position.x;
00087     odom_tf.transform.translation.y = pose_stamped.pose.position.y;
00088     odom_tf.transform.translation.z = pose_stamped.pose.position.z;
00089     odom_tf.transform.rotation = pose_stamped.pose.orientation;
00090 
00091     this->tf_broadcaster.sendTransform(odom_tf);
00092   }
00093 
00094   void RoconTFReconstructor::spin()
00095   {
00096     ROS_INFO("In Spin!");
00097     RoconPoseClient* rpc;
00098     ros::Rate r(spin_rate_);
00099 
00100     while(ros::ok())
00101     {
00102       ros::spinOnce();
00103       std::map<std::string,RoconPoseClient*>::iterator iter;
00104       for(iter = this->sub_clients_pose.begin(); iter != this->sub_clients_pose.end(); ++iter)
00105       {
00106         rpc = iter->second;
00107         if(rpc->isInitialized()) {
00108           std::string client_name = rpc->getClientName();
00109           geometry_msgs::PoseStamped client_pose = rpc->getPoseStamped();
00110 
00111           publishClientTF(client_name,client_pose);
00112         }
00113       }
00114       r.sleep();
00115     }
00116   }
00117 }


rocon_tf_reconstructor
Author(s):
autogenerated on Thu Jun 6 2019 18:17:53