diff --git a/include/publisher_trajectory.h b/include/publisher_trajectory.h index 2d855cbb42558dd6265b50a9ebd70080a623d160..eddfa6073ba7bbdff9f92f34f395173e10311aaa 100644 --- a/include/publisher_trajectory.h +++ b/include/publisher_trajectory.h @@ -50,8 +50,6 @@ class PublisherTrajectory: public Publisher std::string frame_id_; - ros::Publisher pub_path_; - public: PublisherTrajectory(const std::string& _unique_name, const ParamsServer& _server, diff --git a/src/publisher_trajectory.cpp b/src/publisher_trajectory.cpp index 2e460865deae086cc7bdef8db6b6ad449c21c01a..6fa357685b30859115a70d7bbb1c213402e27e1e 100644 --- a/src/publisher_trajectory.cpp +++ b/src/publisher_trajectory.cpp @@ -52,12 +52,12 @@ void PublisherTrajectory::initialize(ros::NodeHandle& nh, const std::string& top // PATH path_msg_.header.frame_id = frame_id_; - pub_path_ = nh.advertise<nav_msgs::Path>(topic, 1); + publisher_ = nh.advertise<nav_msgs::Path>(topic, 1); } void PublisherTrajectory::publishDerived() { - if (pub_path_.getNumSubscribers() != 0 ) + if (publisher_.getNumSubscribers() != 0 ) publishTrajectory(); } @@ -100,7 +100,7 @@ void PublisherTrajectory::publishTrajectory() } //Publish path - pub_path_.publish(path_msg_); + publisher_.publish(path_msg_); //clear msg path_msg_.poses.clear();