Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 #ifndef GET_LANGUAGE_SERVICE_HPP
00020 #define GET_LANGUAGE_SERVICE_HPP
00021
00022 #include <iostream>
00023
00024 #include <ros/node_handle.h>
00025 #include <ros/service_server.h>
00026
00027 #include <naoqi_bridge_msgs/GetString.h>
00028 #include <qi/session.hpp>
00029
00030 namespace naoqi
00031 {
00032 namespace service
00033 {
00034
00035 class GetLanguageService
00036 {
00037 public:
00038 GetLanguageService( const std::string& name, const std::string& topic, const qi::SessionPtr& session );
00039
00040 ~GetLanguageService(){};
00041
00042 std::string name() const
00043 {
00044 return name_;
00045 }
00046
00047 std::string topic() const
00048 {
00049 return topic_;
00050 }
00051
00052 void reset( ros::NodeHandle& nh );
00053
00054 bool callback( naoqi_bridge_msgs::GetStringRequest& req, naoqi_bridge_msgs::GetStringResponse& resp );
00055
00056
00057 private:
00058 const std::string name_;
00059 const std::string topic_;
00060
00061 const qi::SessionPtr& session_;
00062 ros::ServiceServer service_;
00063 };
00064
00065 }
00066 }
00067 #endif