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