Mirror clock API from Node to LifecycleNode (#417)
* Mirror clock API from Node to LifecycleNode Follow up to #407 * adding headers for completeness
This commit is contained in:
		
							parent
							
								
									2e4e85f141
								
							
						
					
					
						commit
						713ee8059c
					
				
					 4 changed files with 44 additions and 2 deletions
				
			
		| 
						 | 
					@ -35,6 +35,7 @@
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#include "rclcpp/callback_group.hpp"
 | 
					#include "rclcpp/callback_group.hpp"
 | 
				
			||||||
#include "rclcpp/client.hpp"
 | 
					#include "rclcpp/client.hpp"
 | 
				
			||||||
 | 
					#include "rclcpp/clock.hpp"
 | 
				
			||||||
#include "rclcpp/context.hpp"
 | 
					#include "rclcpp/context.hpp"
 | 
				
			||||||
#include "rclcpp/event.hpp"
 | 
					#include "rclcpp/event.hpp"
 | 
				
			||||||
#include "rclcpp/logger.hpp"
 | 
					#include "rclcpp/logger.hpp"
 | 
				
			||||||
| 
						 | 
					@ -52,6 +53,7 @@
 | 
				
			||||||
#include "rclcpp/publisher.hpp"
 | 
					#include "rclcpp/publisher.hpp"
 | 
				
			||||||
#include "rclcpp/service.hpp"
 | 
					#include "rclcpp/service.hpp"
 | 
				
			||||||
#include "rclcpp/subscription.hpp"
 | 
					#include "rclcpp/subscription.hpp"
 | 
				
			||||||
 | 
					#include "rclcpp/time.hpp"
 | 
				
			||||||
#include "rclcpp/timer.hpp"
 | 
					#include "rclcpp/timer.hpp"
 | 
				
			||||||
#include "rclcpp/visibility_control.hpp"
 | 
					#include "rclcpp/visibility_control.hpp"
 | 
				
			||||||
 | 
					
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -216,7 +216,6 @@ Node::now()
 | 
				
			||||||
  return node_clock_->get_clock()->now();
 | 
					  return node_clock_->get_clock()->now();
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					 | 
				
			||||||
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
 | 
					rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
 | 
				
			||||||
Node::get_node_base_interface()
 | 
					Node::get_node_base_interface()
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
| 
						 | 
					@ -229,7 +228,6 @@ Node::get_node_clock_interface()
 | 
				
			||||||
  return node_clock_;
 | 
					  return node_clock_;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					 | 
				
			||||||
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
 | 
					rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
 | 
				
			||||||
Node::get_node_graph_interface()
 | 
					Node::get_node_graph_interface()
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -30,12 +30,14 @@
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#include "rclcpp/callback_group.hpp"
 | 
					#include "rclcpp/callback_group.hpp"
 | 
				
			||||||
#include "rclcpp/client.hpp"
 | 
					#include "rclcpp/client.hpp"
 | 
				
			||||||
 | 
					#include "rclcpp/clock.hpp"
 | 
				
			||||||
#include "rclcpp/context.hpp"
 | 
					#include "rclcpp/context.hpp"
 | 
				
			||||||
#include "rclcpp/event.hpp"
 | 
					#include "rclcpp/event.hpp"
 | 
				
			||||||
#include "rclcpp/logger.hpp"
 | 
					#include "rclcpp/logger.hpp"
 | 
				
			||||||
#include "rclcpp/macros.hpp"
 | 
					#include "rclcpp/macros.hpp"
 | 
				
			||||||
#include "rclcpp/message_memory_strategy.hpp"
 | 
					#include "rclcpp/message_memory_strategy.hpp"
 | 
				
			||||||
#include "rclcpp/node_interfaces/node_base_interface.hpp"
 | 
					#include "rclcpp/node_interfaces/node_base_interface.hpp"
 | 
				
			||||||
 | 
					#include "rclcpp/node_interfaces/node_clock_interface.hpp"
 | 
				
			||||||
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
 | 
					#include "rclcpp/node_interfaces/node_graph_interface.hpp"
 | 
				
			||||||
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
 | 
					#include "rclcpp/node_interfaces/node_logging_interface.hpp"
 | 
				
			||||||
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
 | 
					#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
 | 
				
			||||||
| 
						 | 
					@ -46,6 +48,7 @@
 | 
				
			||||||
#include "rclcpp/publisher.hpp"
 | 
					#include "rclcpp/publisher.hpp"
 | 
				
			||||||
#include "rclcpp/service.hpp"
 | 
					#include "rclcpp/service.hpp"
 | 
				
			||||||
#include "rclcpp/subscription.hpp"
 | 
					#include "rclcpp/subscription.hpp"
 | 
				
			||||||
 | 
					#include "rclcpp/time.hpp"
 | 
				
			||||||
#include "rclcpp/timer.hpp"
 | 
					#include "rclcpp/timer.hpp"
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
 | 
					#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
 | 
				
			||||||
| 
						 | 
					@ -326,11 +329,24 @@ public:
 | 
				
			||||||
    rclcpp::event::Event::SharedPtr event,
 | 
					    rclcpp::event::Event::SharedPtr event,
 | 
				
			||||||
    std::chrono::nanoseconds timeout);
 | 
					    std::chrono::nanoseconds timeout);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  RCLCPP_LIFECYCLE_PUBLIC
 | 
				
			||||||
 | 
					  rclcpp::Clock::SharedPtr
 | 
				
			||||||
 | 
					  get_clock();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  RCLCPP_LIFECYCLE_PUBLIC
 | 
				
			||||||
 | 
					  rclcpp::Time
 | 
				
			||||||
 | 
					  now();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  /// Return the Node's internal NodeBaseInterface implementation.
 | 
					  /// Return the Node's internal NodeBaseInterface implementation.
 | 
				
			||||||
  RCLCPP_LIFECYCLE_PUBLIC
 | 
					  RCLCPP_LIFECYCLE_PUBLIC
 | 
				
			||||||
  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
 | 
					  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
 | 
				
			||||||
  get_node_base_interface();
 | 
					  get_node_base_interface();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  /// Return the Node's internal NodeClockInterface implementation.
 | 
				
			||||||
 | 
					  RCLCPP_LIFECYCLE_PUBLIC
 | 
				
			||||||
 | 
					  rclcpp::node_interfaces::NodeClockInterface::SharedPtr
 | 
				
			||||||
 | 
					  get_node_clock_interface();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  /// Return the Node's internal NodeGraphInterface implementation.
 | 
					  /// Return the Node's internal NodeGraphInterface implementation.
 | 
				
			||||||
  RCLCPP_LIFECYCLE_PUBLIC
 | 
					  RCLCPP_LIFECYCLE_PUBLIC
 | 
				
			||||||
  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
 | 
					  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
 | 
				
			||||||
| 
						 | 
					@ -480,6 +496,7 @@ private:
 | 
				
			||||||
  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
 | 
					  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
 | 
				
			||||||
  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
 | 
					  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
 | 
				
			||||||
  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
 | 
					  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
 | 
				
			||||||
 | 
					  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  bool use_intra_process_comms_;
 | 
					  bool use_intra_process_comms_;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -28,6 +28,7 @@
 | 
				
			||||||
#include "rclcpp/logger.hpp"
 | 
					#include "rclcpp/logger.hpp"
 | 
				
			||||||
#include "rclcpp/node.hpp"
 | 
					#include "rclcpp/node.hpp"
 | 
				
			||||||
#include "rclcpp/node_interfaces/node_base.hpp"
 | 
					#include "rclcpp/node_interfaces/node_base.hpp"
 | 
				
			||||||
 | 
					#include "rclcpp/node_interfaces/node_clock.hpp"
 | 
				
			||||||
#include "rclcpp/node_interfaces/node_graph.hpp"
 | 
					#include "rclcpp/node_interfaces/node_graph.hpp"
 | 
				
			||||||
#include "rclcpp/node_interfaces/node_logging.hpp"
 | 
					#include "rclcpp/node_interfaces/node_logging.hpp"
 | 
				
			||||||
#include "rclcpp/node_interfaces/node_parameters.hpp"
 | 
					#include "rclcpp/node_interfaces/node_parameters.hpp"
 | 
				
			||||||
| 
						 | 
					@ -66,6 +67,12 @@ LifecycleNode::LifecycleNode(
 | 
				
			||||||
      node_topics_.get(),
 | 
					      node_topics_.get(),
 | 
				
			||||||
      use_intra_process_comms
 | 
					      use_intra_process_comms
 | 
				
			||||||
    )),
 | 
					    )),
 | 
				
			||||||
 | 
					  node_clock_(new rclcpp::node_interfaces::NodeClock(
 | 
				
			||||||
 | 
					      node_base_,
 | 
				
			||||||
 | 
					      node_topics_,
 | 
				
			||||||
 | 
					      node_graph_,
 | 
				
			||||||
 | 
					      node_services_
 | 
				
			||||||
 | 
					    )),
 | 
				
			||||||
  use_intra_process_comms_(use_intra_process_comms),
 | 
					  use_intra_process_comms_(use_intra_process_comms),
 | 
				
			||||||
  impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_))
 | 
					  impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_))
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
| 
						 | 
					@ -216,12 +223,30 @@ LifecycleNode::wait_for_graph_change(
 | 
				
			||||||
  node_graph_->wait_for_graph_change(event, timeout);
 | 
					  node_graph_->wait_for_graph_change(event, timeout);
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					rclcpp::Clock::SharedPtr
 | 
				
			||||||
 | 
					LifecycleNode::get_clock()
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					  return node_clock_->get_clock();
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					rclcpp::Time
 | 
				
			||||||
 | 
					LifecycleNode::now()
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					  return node_clock_->get_clock()->now();
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
 | 
					rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
 | 
				
			||||||
LifecycleNode::get_node_base_interface()
 | 
					LifecycleNode::get_node_base_interface()
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
  return node_base_;
 | 
					  return node_base_;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					rclcpp::node_interfaces::NodeClockInterface::SharedPtr
 | 
				
			||||||
 | 
					LifecycleNode::get_node_clock_interface()
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					  return node_clock_;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
 | 
					rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
 | 
				
			||||||
LifecycleNode::get_node_graph_interface()
 | 
					LifecycleNode::get_node_graph_interface()
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
		Loading…
	
	Add table
		Add a link
		
	
		Reference in a new issue