Skip to content
Snippets Groups Projects
Commit edc35c30 authored by Joan Vallvé Navarro's avatar Joan Vallvé Navarro
Browse files

subscriber/publisher new API

parent a75c028f
No related branches found
No related tags found
2 merge requests!3After cmake and const refactor,!1new release
......@@ -53,7 +53,7 @@ class SubscriberGnss : public Subscriber
const SensorBasePtr _sensor_ptr);
WOLF_SUBSCRIBER_CREATE(SubscriberGnss);
virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic);
virtual void initialize(ros::NodeHandle& nh, const std::string& topic);
void callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg);
......
......@@ -45,7 +45,7 @@ class SubscriberGnssFix : public Subscriber
const SensorBasePtr _sensor_ptr);
WOLF_SUBSCRIBER_CREATE(SubscriberGnssFix);
virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic);
virtual void initialize(ros::NodeHandle& nh, const std::string& topic);
void callback(const sensor_msgs::NavSatFix::ConstPtr& msg);
};
......
......@@ -41,7 +41,7 @@ class SubscriberGnssNovatel : public SubscriberGnssReceiver
const SensorBasePtr _sensor_ptr);
WOLF_SUBSCRIBER_CREATE(SubscriberGnssNovatel);
virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic);
virtual void initialize(ros::NodeHandle& nh, const std::string& topic);
void callback(const novatel_oem7_msgs::Oem7RawMsg& msg);
......
......@@ -55,7 +55,7 @@ class SubscriberGnssTdcp : public Subscriber
const SensorBasePtr _sensor_ptr);
WOLF_SUBSCRIBER_CREATE(SubscriberGnssTdcp);
virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic);
virtual void initialize(ros::NodeHandle& nh, const std::string& topic);
void callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg);
......
......@@ -41,7 +41,7 @@ class SubscriberGnssUblox : public SubscriberGnssReceiver
const SensorBasePtr _sensor_ptr);
WOLF_SUBSCRIBER_CREATE(SubscriberGnssUblox);
virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic);
virtual void initialize(ros::NodeHandle& nh, const std::string& topic);
void callback(const std_msgs::UInt8MultiArray& msg);
......
......@@ -12,7 +12,7 @@ SubscriberGnss::SubscriberGnss(const std::string& _unique_name,
}
void SubscriberGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
void SubscriberGnss::initialize(ros::NodeHandle& nh, const std::string& topic)
{
sub_ = nh.subscribe(topic+std::string("obs"), 1, &SubscriberGnss::callbackObservation, this);
sub_nav_ = nh.subscribe(topic+std::string("nav"), 1, &SubscriberGnss::callbackNavigation, this);
......
......@@ -12,7 +12,7 @@ SubscriberGnssFix::SubscriberGnssFix(const std::string& _unique_name,
}
void SubscriberGnssFix::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
void SubscriberGnssFix::initialize(ros::NodeHandle& nh, const std::string& topic)
{
sub_ = nh.subscribe(topic, 1, &SubscriberGnssFix::callback, this);
}
......
......@@ -14,7 +14,7 @@ SubscriberGnssNovatel::SubscriberGnssNovatel(const std::string& _unique_name,
{
}
void SubscriberGnssNovatel::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
void SubscriberGnssNovatel::initialize(ros::NodeHandle& nh, const std::string& topic)
{
sub_ = nh.subscribe(topic, 100, &SubscriberGnssNovatel::callback, this);
......
......@@ -12,7 +12,7 @@ SubscriberGnssTdcp::SubscriberGnssTdcp(const std::string& _unique_name,
// TODO copied from Tdcp_ros
}
void SubscriberGnssTdcp::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
void SubscriberGnssTdcp::initialize(ros::NodeHandle& nh, const std::string& topic)
{
sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnssTdcp::callbackObservation, this);
sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnssTdcp::callbackNavigation, this);
......
......@@ -14,7 +14,7 @@ SubscriberGnssUblox::SubscriberGnssUblox(const std::string& _unique_name,
{
}
void SubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
void SubscriberGnssUblox::initialize(ros::NodeHandle& nh, const std::string& topic)
{
sub_ = nh.subscribe(topic, 100, &SubscriberGnssUblox::callback, this);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment