rclcpp
master
C++ ROS Client Library API
|
#include <time_source.hpp>
Public Member Functions | |
TimeSource (rclcpp::Node::SharedPtr node, const rclcpp::QoS &qos=rclcpp::ClockQoS(), bool use_clock_thread=true) | |
Constructor. More... | |
TimeSource (const rclcpp::QoS &qos=rclcpp::ClockQoS(), bool use_clock_thread=true) | |
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... | |
Protected Attributes | |
bool | use_clock_thread_ |
std::thread | clock_executor_thread_ |
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:
|
explicit |
Constructor.
The node will be attached to the time source.
node | std::shared pointer to a initialized node |
qos | QoS that will be used when creating a /clock subscription. |
|
explicit |
Empty constructor.
An Empty TimeSource class
qos | QoS that will be used when creating a /clock subscription. |
rclcpp::TimeSource::~TimeSource | ( | ) |
TimeSource Destructor.
void rclcpp::TimeSource::attachNode | ( | rclcpp::Node::SharedPtr | node | ) |
Attack node to the time source.
node | std::shared pointer to a initialized node |
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.
node_base_interface | Node base interface. |
node_topics_interface | Node topic base interface. |
node_graph_interface | Node graph interface. |
node_services_interface | Node service interface. |
node_logging_interface | Node logging interface. |
node_clock_interface | Node clock interface. |
node_parameters_interface | Node parameters interface. |
void rclcpp::TimeSource::detachNode | ( | ) |
Detach the node from the time source.
void rclcpp::TimeSource::attachClock | ( | rclcpp::Clock::SharedPtr | clock | ) |
Attach a clock to the time source to be updated.
[in] | clock | to attach to the time source |
std::invalid_argument | the time source must be a RCL_ROS_TIME otherwise throws an exception |
void rclcpp::TimeSource::detachClock | ( | rclcpp::Clock::SharedPtr | clock | ) |
Detach a clock to the time source.
|
protected |
|
protected |