Skip to content

Commit a9a5998

Browse files
committed
add steady clock to nodes
1 parent 59de6ff commit a9a5998

File tree

4 files changed

+6
-0
lines changed

4 files changed

+6
-0
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -518,6 +518,7 @@ void ControllerManager::init_distributed_sub_controller_manager()
518518
{
519519
// create node for publishing/subscribing
520520
rclcpp::NodeOptions node_options;
521+
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
521522
distributed_pub_sub_node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
522523
std::string(get_name()) + "_pub_sub_node", get_namespace(), node_options, false);
523524
//try to add to executor
@@ -567,6 +568,7 @@ void ControllerManager::init_distributed_central_controller_manager()
567568
if (!use_multiple_nodes())
568569
{
569570
rclcpp::NodeOptions node_options;
571+
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
570572
distributed_pub_sub_node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
571573
std::string(get_name()) + "_pub_sub_node", get_namespace(), node_options, false);
572574
//try to add to executor

hardware_interface/include/hardware_interface/handle.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -203,6 +203,7 @@ class DistributedReadOnlyHandle : public ReadOnlyHandle
203203
if (!node_.get())
204204
{
205205
rclcpp::NodeOptions node_options;
206+
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
206207
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
207208
get_underscore_separated_name() + "_state_interface_subscriber", namespace_, node_options,
208209
false);
@@ -354,6 +355,7 @@ class DistributedReadWriteHandle : public ReadWriteHandle
354355
if (!node_.get())
355356
{
356357
rclcpp::NodeOptions node_options;
358+
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
357359
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
358360
get_underscore_separated_name() + "_distributed_command_interface", namespace_,
359361
node_options, false);

hardware_interface/src/hardware_interface/distributed_control_interface/command_forwarder.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@ CommandForwarder::CommandForwarder(
2727
if (!node_.get())
2828
{
2929
rclcpp::NodeOptions node_options;
30+
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
3031
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
3132
loaned_command_interface_ptr_->get_underscore_separated_name() + "_command_forwarder",
3233
namespace_, node_options, false);

hardware_interface/src/hardware_interface/distributed_control_interface/state_publisher.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@ StatePublisher::StatePublisher(
2727
if (!node_.get())
2828
{
2929
rclcpp::NodeOptions node_options;
30+
node_options.clock_type(rcl_clock_type_t::RCL_STEADY_TIME);
3031
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
3132
loaned_state_interface_ptr_->get_underscore_separated_name() + "_state_publisher", namespace_,
3233
node_options, false);

0 commit comments

Comments
 (0)