23 #include <boost/make_shared.hpp> 24 #include <boost/shared_ptr.hpp> 61 std::cout <<
name() <<
" is resetting" << std::endl;
63 std::cout <<
name() <<
" reset" << std::endl;
93 virtual std::string
name()
const = 0;
94 virtual std::string
topic()
const = 0;
110 return service_->name();
115 return service_->topic();
120 return service_->isInitialized();
125 service_->reset( nh );
void reset(ros::NodeHandle &nh)
initializes/resets the service into ROS with a given nodehandle, this will be called at first for ini...
void reset(ros::NodeHandle &nh)
std::string topic() const
std::string name() const
getting the descriptive name for this service instance
std::string topic() const
getting the topic to service on
boost::shared_ptr< ServiceConcept > srvPtr_
virtual ~ServiceConcept()
virtual void reset(ros::NodeHandle &nh)=0
bool isInitialized() const
ServiceModel(const T &other)
virtual std::string name() const =0
Service(T srv)
Constructor for service interface.
Service concept interface.
virtual std::string topic() const =0