Program Listing for File subscriber.hpp
↰ Return to documentation for file (include/naoqi_driver/subscriber/subscriber.hpp)
/*
* Copyright 2015 Aldebaran
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef SUBSCRIBER_HPP
#define SUBSCRIBER_HPP
#include <string>
#include <boost/make_shared.hpp>
#include <boost/shared_ptr.hpp>
#include <rclcpp/rclcpp.hpp>
namespace naoqi
{
namespace subscriber
{
class Subscriber
{
public:
template<typename T>
Subscriber( T sub ):
subPtr_( boost::make_shared<SubscriberModel<T> >(sub) )
{}
bool isInitialized() const
{
return subPtr_->isInitialized();
}
void reset( rclcpp::Node* node )
{
std::cout << name() << " is resetting" << std::endl;
subPtr_->reset( node );
std::cout << name() << " reset" << std::endl;
}
std::string name() const
{
return subPtr_->name();
}
std::string topic() const
{
return subPtr_->topic();
}
friend bool operator==( const Subscriber& lhs, const Subscriber& rhs )
{
// decision made for OR-comparison since we want to be more restrictive
if ( lhs.name() == rhs.name() || lhs.topic() == rhs.topic() )
return true;
return false;
}
private:
struct SubscriberConcept
{
virtual ~SubscriberConcept(){}
virtual bool isInitialized() const = 0;
virtual void reset( rclcpp::Node* node ) = 0;
virtual std::string name() const = 0;
virtual std::string topic() const = 0;
};
template<typename T>
struct SubscriberModel : public SubscriberConcept
{
SubscriberModel( const T& other ):
subscriber_( other )
{}
std::string name() const
{
return subscriber_->name();
}
std::string topic() const
{
return subscriber_->topic();
}
bool isInitialized() const
{
return subscriber_->isInitialized();
}
void reset( rclcpp::Node* node )
{
subscriber_->reset( node );
}
T subscriber_;
};
boost::shared_ptr<SubscriberConcept> subPtr_;
}; // class subscriber
} //subscriber
} //naoqi
#endif