ros2_control - rolling
Loading...
Searching...
No Matches
heartbeat_publisher_plugin.hpp
1// Copyright 2026 PAL Robotics S.L.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef MUJOCO_ROS2_CONTROL_PLUGINS__HEARTBEAT_PUBLISHER_PLUGIN_HPP_
16#define MUJOCO_ROS2_CONTROL_PLUGINS__HEARTBEAT_PUBLISHER_PLUGIN_HPP_
17
18#include <rclcpp/rclcpp.hpp>
19#include <std_msgs/msg/string.hpp>
20#include "mujoco_ros2_control_plugins/mujoco_ros2_control_plugins_base.hpp"
21
22namespace mujoco_ros2_control_plugins
23{
24
29{
30public:
31 HeartbeatPublisherPlugin() = default;
32 ~HeartbeatPublisherPlugin() override = default;
33
37 bool init(rclcpp::Node::SharedPtr node, const mjModel* model, mjData* data) override;
38
42 void update(const mjModel* model, mjData* data) override;
43
47 void cleanup() override;
48
49private:
50 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr heartbeat_publisher_;
51 rclcpp::Node::SharedPtr node_;
52 rclcpp::Logger logger_ = rclcpp::get_logger("HeartbeatPublisherPlugin");
53 rclcpp::Time last_publish_time_;
54 rclcpp::Duration publish_period_{ 1, 0 }; // Publish every 1 second
55 uint64_t message_count_{ 0 };
56};
57
58} // namespace mujoco_ros2_control_plugins
59
60#endif // MUJOCO_ROS2_CONTROL_PLUGINS__HEARTBEAT_PUBLISHER_PLUGIN_HPP_
Simple plugin that publishes a heartbeat message every second.
Definition heartbeat_publisher_plugin.hpp:29
void cleanup() override
Cleanup the plugin.
Definition heartbeat_publisher_plugin.cpp:60
bool init(rclcpp::Node::SharedPtr node, const mjModel *model, mjData *data) override
Initialize the plugin.
Definition heartbeat_publisher_plugin.cpp:21
void update(const mjModel *model, mjData *data) override
Update the plugin (called every simulation step)
Definition heartbeat_publisher_plugin.cpp:39
Base class for MuJoCo ROS 2 control plugins.
Definition mujoco_ros2_control_plugins_base.hpp:32