From 04dd2a0494f237ae8e2e672ded33736230d989cd Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Thu, 16 Nov 2023 07:34:59 +0100 Subject: [PATCH] Inlining node loop again. --- include/t07_robot/Node.h | 6 ++---- src/Node.cpp | 15 +++++++-------- 2 files changed, 9 insertions(+), 12 deletions(-) diff --git a/include/t07_robot/Node.h b/include/t07_robot/Node.h index 60b856f..a9d42a9 100644 --- a/include/t07_robot/Node.h +++ b/include/t07_robot/Node.h @@ -52,10 +52,8 @@ class Node : public rclcpp::Node std::mutex _node_mtx; std::chrono::steady_clock::time_point const _node_start; std::unique_ptr _can_mgr; - - static std::chrono::milliseconds constexpr IO_LOOP_RATE{1}; - rclcpp::TimerBase::SharedPtr _io_loop_timer; - void io_loop(); + static std::chrono::milliseconds constexpr NODE_LOOP_RATE{1}; + rclcpp::TimerBase::SharedPtr _node_loop_timer; cyphal::Publisher _cyphal_heartbeat_pub; static std::chrono::milliseconds constexpr CYPHAL_HEARTBEAT_PERIOD{1000}; diff --git a/src/Node.cpp b/src/Node.cpp index d5237e6..ce464a0 100644 --- a/src/Node.cpp +++ b/src/Node.cpp @@ -66,11 +66,16 @@ Node::Node() _node_hdl.onCanFrameReceived(frame); }); + _node_loop_timer = create_wall_timer(NODE_LOOP_RATE, + [this]() + { + std::lock_guard lock(_node_mtx); + _node_hdl.spinSome(); + }); + init_cyphal_heartbeat(); init_cyphal_node_info(); - _io_loop_timer = create_wall_timer(IO_LOOP_RATE, [this]() { this->io_loop(); }); - init_motor_left(); init_motor_right(); @@ -86,12 +91,6 @@ Node::~Node() * PRIVATE MEMBER FUNCTIONS **************************************************************************************/ -void Node::io_loop() -{ - std::lock_guard lock(_node_mtx); - _node_hdl.spinSome(); -} - void Node::init_cyphal_heartbeat() { _cyphal_heartbeat_pub = _node_hdl.create_publisher(1*1000*1000UL /* = 1 sec in usecs. */);