00001 #include<rocon_tf_reconstructor/rocon_pose_client.h> 00002 00003 namespace rocon { 00004 00005 RoconPoseClient::RoconPoseClient() 00006 { 00007 this->initialized = false; 00008 } 00009 00010 RoconPoseClient::RoconPoseClient(ros::NodeHandle& nh,std::string client_name,std::string pose_topic) 00011 { 00012 ros::NodeHandle n; 00013 std::string topic_name = "/" + client_name + "/" + pose_topic; 00014 00015 this->initialized = false; 00016 this->client_name = client_name; 00017 this->pose_topic = pose_topic; 00018 this->sub = n.subscribe(topic_name,10,&RoconPoseClient::processPose,this); 00019 } 00020 00021 RoconPoseClient::~RoconPoseClient() 00022 { 00023 this->sub.shutdown(); 00024 } 00025 00026 00027 void RoconPoseClient::processPose(const geometry_msgs::PoseStamped::ConstPtr msg) 00028 { 00029 this->initialized = true; 00030 this->pose_stamped = *msg; 00031 } 00032 00033 geometry_msgs::PoseStamped RoconPoseClient::getPoseStamped() 00034 { 00035 return this->pose_stamped; 00036 } 00037 00038 std::string RoconPoseClient::getClientName() 00039 { 00040 return this->client_name; 00041 } 00042 00043 bool RoconPoseClient::isInitialized() 00044 { 00045 return this->initialized; 00046 } 00047 }