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