Create node clock calls const (try 2) (#922)

* create node clock calls const

Signed-off-by: stevemacenski <stevenmacenski@gmail.com>

* two methods for get clock, one const

Signed-off-by: stevemacenski <stevenmacenski@gmail.com>

* changing APIs for NodeClock and NodeClockInterface

Signed-off-by: stevemacenski <stevenmacenski@gmail.com>

* changing RCLCPP_LIFECYCLE_PUBLIC from RCLCPP_PUBLIC for rclcpp lifecycle node get_clock const method

Signed-off-by: stevemacenski <stevenmacenski@gmail.com>
This commit is contained in:
Steven Macenski 2019-12-06 14:03:58 -08:00 committed by Dirk Thomas
parent 6ba0f59fed
commit 9d5947108b
7 changed files with 43 additions and 5 deletions

View file

@ -894,9 +894,13 @@ public:
rclcpp::Clock::SharedPtr rclcpp::Clock::SharedPtr
get_clock(); get_clock();
RCLCPP_PUBLIC
rclcpp::Clock::ConstSharedPtr
get_clock() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
Time Time
now(); now() const;
/// Return the Node's internal NodeBaseInterface implementation. /// Return the Node's internal NodeBaseInterface implementation.
RCLCPP_PUBLIC RCLCPP_PUBLIC

View file

@ -54,6 +54,12 @@ public:
rclcpp::Clock::SharedPtr rclcpp::Clock::SharedPtr
get_clock() override; get_clock() override;
/// Get a clock which will be kept up to date by the node.
RCLCPP_PUBLIC
virtual
rclcpp::Clock::ConstSharedPtr
get_clock() const;
private: private:
RCLCPP_DISABLE_COPY(NodeClock) RCLCPP_DISABLE_COPY(NodeClock)

View file

@ -40,6 +40,12 @@ public:
virtual virtual
rclcpp::Clock::SharedPtr rclcpp::Clock::SharedPtr
get_clock() = 0; get_clock() = 0;
/// Get a const ROS clock which will be kept up to date by the node.
RCLCPP_PUBLIC
virtual
rclcpp::Clock::ConstSharedPtr
get_clock() const = 0;
}; };
} // namespace node_interfaces } // namespace node_interfaces

View file

@ -390,8 +390,14 @@ Node::get_clock()
return node_clock_->get_clock(); return node_clock_->get_clock();
} }
rclcpp::Clock::ConstSharedPtr
Node::get_clock() const
{
return node_clock_->get_clock();
}
rclcpp::Time rclcpp::Time
Node::now() Node::now() const
{ {
return node_clock_->get_clock()->now(); return node_clock_->get_clock()->now();
} }

View file

@ -36,8 +36,14 @@ NodeClock::NodeClock(
NodeClock::~NodeClock() NodeClock::~NodeClock()
{} {}
std::shared_ptr<rclcpp::Clock> rclcpp::Clock::SharedPtr
NodeClock::get_clock() NodeClock::get_clock()
{ {
return ros_clock_; return ros_clock_;
} }
rclcpp::Clock::ConstSharedPtr
NodeClock::get_clock() const
{
return ros_clock_;
}

View file

@ -465,9 +465,13 @@ public:
rclcpp::Clock::SharedPtr rclcpp::Clock::SharedPtr
get_clock(); get_clock();
RCLCPP_LIFECYCLE_PUBLIC
rclcpp::Clock::ConstSharedPtr
get_clock() const;
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::Time rclcpp::Time
now(); now() const;
/// Return the Node's internal NodeBaseInterface implementation. /// Return the Node's internal NodeBaseInterface implementation.
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC

View file

@ -316,8 +316,14 @@ LifecycleNode::get_clock()
return node_clock_->get_clock(); return node_clock_->get_clock();
} }
rclcpp::Clock::ConstSharedPtr
LifecycleNode::get_clock() const
{
return node_clock_->get_clock();
}
rclcpp::Time rclcpp::Time
LifecycleNode::now() LifecycleNode::now() const
{ {
return node_clock_->get_clock()->now(); return node_clock_->get_clock()->now();
} }