diff --git a/include/subscriber_imu.h b/include/subscriber_imu.h index 7168a12f8e7a20c09c65ac7699125b06e1f2d4d9..04046d87048717485714690c8f5e038187a0c437 100644 --- a/include/subscriber_imu.h +++ b/include/subscriber_imu.h @@ -44,7 +44,7 @@ class SubscriberImu : public Subscriber const SensorBasePtr _sensor_ptr); WOLF_SUBSCRIBER_CREATE(SubscriberImu); - 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::Imu::ConstPtr& msg); }; diff --git a/include/subscriber_imu_enablable.h b/include/subscriber_imu_enablable.h index bfc6b3ec1680578a6519e20303986d3041740e5a..001fee91735d1405c72b01fca74368a8f6977c81 100644 --- a/include/subscriber_imu_enablable.h +++ b/include/subscriber_imu_enablable.h @@ -47,7 +47,7 @@ class SubscriberImuEnablable : public SubscriberImu const SensorBasePtr _sensor_ptr); WOLF_SUBSCRIBER_CREATE(SubscriberImuEnablable); - 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::Imu::ConstPtr& msg); diff --git a/src/subscriber_imu.cpp b/src/subscriber_imu.cpp index e18a24f43fc00e1333a1f293402b7a88f7ed79dc..b190b1ca312f7891250faf1aa408dd858a802675 100644 --- a/src/subscriber_imu.cpp +++ b/src/subscriber_imu.cpp @@ -13,7 +13,7 @@ SubscriberImu::SubscriberImu(const std::string& _unique_name, flip_x_axis_ = _server.getParam<bool>(prefix_ + "/flip_x_axis"); } -void SubscriberImu::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberImu::initialize(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic, 1, &SubscriberImu::callback, this); } diff --git a/src/subscriber_imu_enablable.cpp b/src/subscriber_imu_enablable.cpp index 7e686e4c702004249f9179d3b06d44b42c26cef4..69c3bacf80cab7a22bdab5c2f54abab8b0f5ed5a 100644 --- a/src/subscriber_imu_enablable.cpp +++ b/src/subscriber_imu_enablable.cpp @@ -13,7 +13,7 @@ SubscriberImuEnablable::SubscriberImuEnablable(const std::string& _unique_name, topic_enable_ = _server.getParam<std::string>(prefix_ + "/topic_enable"); } -void SubscriberImuEnablable::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberImuEnablable::initialize(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic, 1, &SubscriberImuEnablable::callback, this); enable_sub_ = nh.subscribe(topic_enable_, 1, &SubscriberImuEnablable::enableCallback, this);