rclcpp  master
C++ ROS Client Library API
Public Member Functions | List of all members
rclcpp::TimeSource Class Reference

#include <time_source.hpp>

Public Member Functions

 TimeSource (rclcpp::Node::SharedPtr node)
 Constructor. More...
 
 TimeSource ()
 Empty constructor. More...
 
void attachNode (rclcpp::Node::SharedPtr node)
 Attack node to the time source. More...
 
void attachNode (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface)
 Attack node to the time source. More...
 
void detachNode ()
 Detach the node from the time source. More...
 
void attachClock (rclcpp::Clock::SharedPtr clock)
 Attach a clock to the time source to be updated. More...
 
void detachClock (rclcpp::Clock::SharedPtr clock)
 Detach a clock to the time source. More...
 
 ~TimeSource ()
 TimeSource Destructor. More...
 

Constructor & Destructor Documentation

◆ TimeSource() [1/2]

rclcpp::TimeSource::TimeSource ( rclcpp::Node::SharedPtr  node)
explicit

Constructor.

The node will be attached to the time source.

Parameters
nodestd::shared pointer to a initialized node

◆ TimeSource() [2/2]

rclcpp::TimeSource::TimeSource ( )

Empty constructor.

An Empty TimeSource class

◆ ~TimeSource()

rclcpp::TimeSource::~TimeSource ( )

TimeSource Destructor.

Member Function Documentation

◆ attachNode() [1/2]

void rclcpp::TimeSource::attachNode ( rclcpp::Node::SharedPtr  node)

Attack node to the time source.

Parameters
nodestd::shared pointer to a initialized node

◆ attachNode() [2/2]

void rclcpp::TimeSource::attachNode ( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node_base_interface,
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr  node_topics_interface,
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr  node_graph_interface,
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr  node_services_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr  node_logging_interface,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr  node_clock_interface,
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr  node_parameters_interface 
)

Attack node to the time source.

If the parameter use_sim_time is true then the source time is the simulation time, otherwise the source time is defined by the system.

Parameters
node_base_interfaceNode base interface.
node_topics_interfaceNode topic base interface.
node_graph_interfaceNode graph interface.
node_services_interfaceNode service interface.
node_logging_interfaceNode logging interface.
node_clock_interfaceNode clock interface.
node_parameters_interfaceNode parameters interface.

◆ detachNode()

void rclcpp::TimeSource::detachNode ( )

Detach the node from the time source.

◆ attachClock()

void rclcpp::TimeSource::attachClock ( rclcpp::Clock::SharedPtr  clock)

Attach a clock to the time source to be updated.

Parameters
[in]clockto attach to the time source
Exceptions
std::invalid_argumentthe time source must be a RCL_ROS_TIME otherwise throws an exception

◆ detachClock()

void rclcpp::TimeSource::detachClock ( rclcpp::Clock::SharedPtr  clock)

Detach a clock to the time source.


The documentation for this class was generated from the following file: