Go to the documentation of this file.00001 #include <ros/ros.h>
00002 #include <rfnserver/rfnserver.h>
00003 #include <std_msgs/String.h>
00004 #include <roboframenet_msgs/FilledSemanticFrameAction.h>
00005
00006 class PingAction {
00007 protected:
00008 rfnserver::RFNServer rs_;
00009 std::string action_name_;
00010 roboframenet_msgs::FilledSemanticFrameFeedback feedback_;
00011 roboframenet_msgs::FilledSemanticFrameResult result_;
00012
00013 public:
00014 PingAction(ros::NodeHandle nh, std::string name) :
00015 rs_(nh, name, boost::bind(&PingAction::executeCB, this, _1)),
00016 action_name_(name)
00017 {
00018 rs_.add_frame("../frames/pinging.yaml");
00019 rs_.add_lexical_unit("../lu/ping_pinging.yaml");
00020 rs_.register_with_frame("pinging");
00021 rs_.start();
00022 }
00023
00024 ~PingAction(void) {}
00025
00026 void executeCB(const roboframenet_msgs::FilledSemanticFrame &frame) {
00027 ROS_INFO("Ping!");
00028 result_.success = true;
00029 rs_.setSucceeded(result_);
00030 }
00031 };
00032
00033 int main(int argc, char** argv) {
00034 ros::init(argc, argv, "ping_topic");
00035 ros::NodeHandle nh;
00036 PingAction ping(nh, ros::this_node::getName());
00037 ros::spin();
00038
00039 return 0;
00040 }
00041