Go to the documentation of this file.
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;
void reset(ros::NodeHandle &nh)
Service concept interface.
std::string name() const
getting the descriptive name for this service instance
virtual ~ServiceConcept()
ServiceModel(const T &other)
void reset(ros::NodeHandle &nh)
initializes/resets the service into ROS with a given nodehandle, this will be called at first for ini...
boost::shared_ptr< ServiceConcept > srvPtr_
Service(T srv)
Constructor for service interface.
virtual void reset(ros::NodeHandle &nh)=0
std::string topic() const
bool isInitialized() const
virtual std::string name() const =0
std::string topic() const
getting the topic to service on
virtual std::string topic() const =0
naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06