ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
Classes | Public Member Functions | List of all members
rclcpp::TimeSource Class Reference

#include <rclcpp/time_source.hpp>

Classes

class  NodeState
 

Public Member Functions

RCLCPP_PUBLIC TimeSource (rclcpp::Node::SharedPtr node, const rclcpp::QoS &qos=rclcpp::ClockQoS(), bool use_clock_thread=true)
 Constructor. More...
 
RCLCPP_PUBLIC TimeSource (const rclcpp::QoS &qos=rclcpp::ClockQoS(), bool use_clock_thread=true)
 Empty constructor. More...
 
 TimeSource (const TimeSource &)=delete
 
TimeSourceoperator= (const TimeSource &)=delete
 
 TimeSource (TimeSource &&)=default
 
TimeSourceoperator= (TimeSource &&)=default
 
RCLCPP_PUBLIC void attachNode (rclcpp::Node::SharedPtr node)
 Attach node to the time source. More...
 
RCLCPP_PUBLIC 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)
 Attach node to the time source. More...
 
RCLCPP_PUBLIC void detachNode ()
 Detach the node from the time source.
 
RCLCPP_PUBLIC void attachClock (rclcpp::Clock::SharedPtr clock)
 Attach a clock to the time source to be updated. More...
 
RCLCPP_PUBLIC void detachClock (rclcpp::Clock::SharedPtr clock)
 Detach a clock from the time source.
 
RCLCPP_PUBLIC bool get_use_clock_thread ()
 Get whether a separate clock thread is used or not.
 
RCLCPP_PUBLIC void set_use_clock_thread (bool use_clock_thread)
 Set whether to use a separate clock thread or not.
 
RCLCPP_PUBLIC bool clock_thread_is_joinable ()
 Check if the clock thread is joinable.
 
RCLCPP_PUBLIC ~TimeSource ()
 TimeSource Destructor.
 

Detailed Description

Time source that will drive the attached clocks.

If the attached node use_sim_time parameter is true, the attached clocks will be updated based on messages received.

The subscription to the clock topic created by the time source can have it's qos reconfigured using parameter overrides, particularly the following ones are accepted:

Definition at line 50 of file time_source.hpp.

Constructor & Destructor Documentation

◆ TimeSource() [1/2]

RCLCPP_PUBLIC rclcpp::TimeSource::TimeSource ( rclcpp::Node::SharedPtr  node,
const rclcpp::QoS qos = rclcpp::ClockQoS(),
bool  use_clock_thread = true 
)
explicit

Constructor.

The node will be attached to the time source.

Parameters
nodestd::shared pointer to a initialized node
qosQoS that will be used when creating a /clock subscription.
use_clock_threadwhether to spin the attached node in a separate thread

◆ TimeSource() [2/2]

rclcpp::TimeSource::TimeSource ( const rclcpp::QoS qos = rclcpp::ClockQoS(),
bool  use_clock_thread = true 
)
explicit

Empty constructor.

An Empty TimeSource class

Parameters
qosQoS that will be used when creating a /clock subscription.
use_clock_threadwhether to spin the attached node in a separate thread.

Definition at line 476 of file time_source.cpp.

Member Function Documentation

◆ 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

Definition at line 525 of file time_source.cpp.

◆ attachNode() [1/2]

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

Attach node to the time source.

Parameters
nodestd::shared pointer to a initialized node

Definition at line 485 of file time_source.cpp.

◆ 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 
)

Attach 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.

Definition at line 498 of file time_source.cpp.


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