00001 00028 #include <ros/ros.h> 00029 00030 #include <string> 00031 #include <sstream> 00032 00033 #include "cyberglove/cyberglove_publisher.h" 00034 #include "cyberglove/cyberglove_service.h" 00035 00036 using namespace ros; 00037 00038 namespace cyberglove{ 00039 00040 CybergloveService::CybergloveService(boost::shared_ptr<CyberglovePublisher> publish) 00041 : node("~"), pub(publish) 00042 { 00043 service_start = node.advertiseService("start",&CybergloveService::start,this); 00044 service_calibration = node.advertiseService("calibration", &CybergloveService::calibration, this); 00045 ROS_INFO("Listening for service"); 00046 } 00047 00048 bool CybergloveService::start(cyberglove::Start::Request &req, cyberglove::Start::Response &res){ 00049 if(req.start){ 00050 ROS_INFO("Glove is now publishing"); 00051 this->pub->setPublishing(true); 00052 } 00053 else{ 00054 ROS_INFO("Glove has stopped publishing"); 00055 this->pub->setPublishing(false); 00056 } 00057 //this->pub->cyberglove_pub.shutdown(); 00058 return true; 00059 } 00060 bool CybergloveService::calibration(cyberglove::Calibration::Request &req, cyberglove::Calibration::Response &res){ 00061 this->pub->setPublishing(false); 00062 this->pub->initialize_calibration(req.path); 00063 this->pub->setPublishing(true); 00064 return true; 00065 } 00066 }