Go to the documentation of this file.00001
00002 namespace rfnserver {
00003
00004 RFNServer::RFNServer(ros::NodeHandle nh, std::string callback_topic, FSFCallback fsf_callback) :
00005 actionlib::SimpleActionServer<roboframenet_msgs::FilledSemanticFrameAction>(nh, callback_topic, boost::bind(&RFNServer::executeCB, this, _1), false),
00006 nh_(nh),
00007 callback_topic_(callback_topic),
00008 fsf_callback_(fsf_callback) {}
00009
00010 void RFNServer::executeCB(const roboframenet_msgs::FilledSemanticFrameGoalConstPtr &goal) {
00011 fsf_callback_(goal->frame);
00012 }
00013
00014 bool RFNServer::add_frame(std::string filepath) {
00015
00016 boost::filesystem::path path(filepath);
00017 boost::filesystem::path abs_path(boost::filesystem::system_complete(path));
00018
00019
00020 ros::ServiceClient client = nh_.serviceClient<roboframenet_msgs::AddFrame>("add_frame");
00021 client.waitForExistence();
00022 roboframenet_msgs::AddFrame srv;
00023 srv.request.absolute_file_path = abs_path.string();
00024 bool is_success = client.call(srv);
00025 if(is_success) {
00026 is_success = srv.response.success;
00027 }
00028 else {
00029 ROS_ERROR("Service call failed!");
00030 }
00031 return is_success;
00032 }
00033
00034
00035 bool RFNServer::add_lexical_unit(std::string filepath) {
00036
00037 boost::filesystem::path path(filepath);
00038 boost::filesystem::path abs_path(boost::filesystem::system_complete(path));
00039
00040 ros::ServiceClient client = nh_.serviceClient<roboframenet_msgs::AddLexicalUnit>("add_lexical_unit");
00041 client.waitForExistence();
00042 roboframenet_msgs::AddLexicalUnit srv;
00043 srv.request.absolute_file_path = abs_path.string();
00044 bool is_success = client.call(srv);
00045 if(is_success) {
00046 is_success = srv.response.success;
00047 }
00048 else {
00049 ROS_ERROR("Service call failed!");
00050 }
00051 return is_success;
00052 }
00053
00054 bool RFNServer::register_with_frame(std::string frame_name) {
00055
00056 ros::ServiceClient client = nh_.serviceClient<roboframenet_msgs::RegisterWithFrame>("register_with_frame");
00057 client.waitForExistence();
00058 roboframenet_msgs::RegisterWithFrame srv;
00059 srv.request.frame_name = frame_name;
00060 srv.request.callback_topic = callback_topic_;
00061 bool is_success = client.call(srv);
00062 if(is_success) {
00063 is_success = srv.response.success;
00064 }
00065 else {
00066 ROS_ERROR("Service call failed!");
00067 }
00068 return is_success;
00069 }
00070
00071 std::string RFNServer::frame_argument(roboframenet_msgs::FilledSemanticFrame frame, std::string parameter_name) {
00072
00073 int num_elements = frame.frame_elements.size();
00074 for(int i=0; i<num_elements; i++) {
00075 if(!parameter_name.compare(frame.frame_elements[i].name)) {
00076 return frame.frame_elements[i].argument;
00077 }
00078 }
00079
00080 return "";
00081 }
00082
00083
00084 };
00085
00086
00087