Class TimeSource

Class Documentation

class TimeSource

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:

  • qos_overrides./clock.depth

  • qos_overrides./clock.durability

  • qos_overrides./clock.history

  • qos_overrides./clock.reliability

Public Functions

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

Constructor.

The node will be attached to the time source.

Parameters:
  • node – std::shared pointer to a initialized node

  • qosQoS that will be used when creating a /clock subscription.

  • use_clock_thread – whether to spin the attached node in a separate thread

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

Empty constructor.

An Empty TimeSource class

Parameters:
  • qosQoS that will be used when creating a /clock subscription.

  • use_clock_thread – whether to spin the attached node in a separate thread.

TimeSource(const TimeSource&) = delete
TimeSource &operator=(const TimeSource&) = delete
TimeSource(TimeSource&&) = default
TimeSource &operator=(TimeSource&&) = default
void attachNode(rclcpp::Node::SharedPtr node)

Attach node to the time source.

Parameters:

node – std::shared pointer to a initialized node

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.

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.

void detachNode()

Detach the node from the time source.

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

Attach a clock to the time source to be updated.

Parameters:

clock[in] to attach to the time source

Throws:

std::invalid_argument – the time source must be a RCL_ROS_TIME otherwise throws an exception

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

Detach a clock from the time source.

bool get_use_clock_thread()

Get whether a separate clock thread is used or not.

void set_use_clock_thread(bool use_clock_thread)

Set whether to use a separate clock thread or not.

bool clock_thread_is_joinable()

Check if the clock thread is joinable.

~TimeSource()

TimeSource Destructor.