23 #include <boost/make_shared.hpp>
24 #include <boost/shared_ptr.hpp>
59 void reset( ros::NodeHandle& nh )
61 std::cout <<
name() <<
" is resetting" << std::endl;
91 virtual void reset( ros::NodeHandle& nh ) = 0;
92 virtual std::string
name()
const = 0;
93 virtual std::string
topic()
const = 0;
void reset(ros::NodeHandle &nh)
initializes/resets the service into ROS with a given nodehandle, this will be called at first for ini...
Definition: service.hpp:59
void reset(ros::NodeHandle &nh)
Definition: service.hpp:122
std::string topic() const
Definition: service.hpp:112
std::string name() const
getting the descriptive name for this service instance
Definition: service.hpp:69
std::string topic() const
getting the topic to service on
Definition: service.hpp:78
boost::shared_ptr< ServiceConcept > srvPtr_
Definition: service.hpp:130
T service_
Definition: service.hpp:127
std::string name() const
Definition: service.hpp:107
virtual ~ServiceConcept()
Definition: service.hpp:90
Definition: service.hpp:88
virtual void reset(ros::NodeHandle &nh)=0
bool isInitialized() const
Definition: service.hpp:117
ServiceModel(const T &other)
Definition: service.hpp:103
virtual std::string name() const =0
Definition: service.hpp:101
Service(T srv)
Constructor for service interface.
Definition: service.hpp:50
Service concept interface.
Definition: service.hpp:41
virtual std::string topic() const =0