15#ifndef MUJOCO_ROS2_CONTROL_PLUGINS__HEARTBEAT_PUBLISHER_PLUGIN_HPP_
16#define MUJOCO_ROS2_CONTROL_PLUGINS__HEARTBEAT_PUBLISHER_PLUGIN_HPP_
18#include <rclcpp/rclcpp.hpp>
19#include <std_msgs/msg/string.hpp>
20#include "mujoco_ros2_control_plugins/mujoco_ros2_control_plugins_base.hpp"
22namespace mujoco_ros2_control_plugins
37 bool init(rclcpp::Node::SharedPtr node,
const mjModel* model, mjData* data)
override;
42 void update(
const mjModel* model, mjData* data)
override;
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 };
55 uint64_t message_count_{ 0 };
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