#include <time_source.hpp>
|
| TimeSource (rclcpp::Node::SharedPtr node) |
|
| TimeSource () |
|
void | attachNode (rclcpp::Node::SharedPtr 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) |
|
void | detachNode () |
|
void | attachClock (rclcpp::Clock::SharedPtr clock) |
| Attach a clock to the time source to be updated. More...
|
|
void | detachClock (rclcpp::Clock::SharedPtr clock) |
|
| ~TimeSource () |
|
◆ TimeSource() [1/2]
rclcpp::TimeSource::TimeSource |
( |
rclcpp::Node::SharedPtr |
node | ) |
|
|
explicit |
◆ TimeSource() [2/2]
rclcpp::TimeSource::TimeSource |
( |
| ) |
|
◆ ~TimeSource()
rclcpp::TimeSource::~TimeSource |
( |
| ) |
|
◆ attachNode() [1/2]
void rclcpp::TimeSource::attachNode |
( |
rclcpp::Node::SharedPtr |
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 |
|
) |
| |
◆ detachNode()
void rclcpp::TimeSource::detachNode |
( |
| ) |
|
◆ attachClock()
void rclcpp::TimeSource::attachClock |
( |
rclcpp::Clock::SharedPtr |
clock | ) |
|
Attach a clock to the time source to be updated.
- Exceptions
-
◆ detachClock()
void rclcpp::TimeSource::detachClock |
( |
rclcpp::Clock::SharedPtr |
clock | ) |
|
The documentation for this class was generated from the following file: