ros2_control - rolling
Loading...
Searching...
No Matches
Public Member Functions | List of all members
mujoco_ros2_control_plugins::MuJoCoROS2ControlPluginBase Class Referenceabstract

Base class for MuJoCo ROS 2 control plugins. More...

#include <mujoco_ros2_control_plugins_base.hpp>

Inheritance diagram for mujoco_ros2_control_plugins::MuJoCoROS2ControlPluginBase:
Inheritance graph
[legend]

Public Member Functions

virtual bool init (rclcpp::Node::SharedPtr node, const mjModel *model, mjData *data)=0
 Initialize the plugin.
 
virtual void update (const mjModel *model, mjData *data)=0
 Update the plugin (called every simulation step)
 
virtual void cleanup ()=0
 Cleanup the plugin.
 

Detailed Description

Base class for MuJoCo ROS 2 control plugins.

This is an example base class that plugins can inherit from. Plugins can extend the functionality of mujoco_ros2_control by implementing custom behaviors.

Member Function Documentation

◆ cleanup()

virtual void mujoco_ros2_control_plugins::MuJoCoROS2ControlPluginBase::cleanup ( )
pure virtual

Cleanup the plugin.

Implemented in mujoco_ros2_control_plugins::HeartbeatPublisherPlugin.

◆ init()

virtual bool mujoco_ros2_control_plugins::MuJoCoROS2ControlPluginBase::init ( rclcpp::Node::SharedPtr  node,
const mjModel *  model,
mjData *  data 
)
pure virtual

Initialize the plugin.

Parameters
nodeShared pointer to the ROS 2 node for accessing parameters
modelPointer to the MuJoCo model
dataPointer to the MuJoCo data
Returns
true if initialization was successful
Note
This method will be called once when the plugin is loaded. It can be used to read parameters, set up publishers/subscribers, etc. The node will be a child of the main mujoco_ros2_control node, so parameters should be namespaced accordingly.

Implemented in mujoco_ros2_control_plugins::HeartbeatPublisherPlugin.

◆ update()

virtual void mujoco_ros2_control_plugins::MuJoCoROS2ControlPluginBase::update ( const mjModel *  model,
mjData *  data 
)
pure virtual

Update the plugin (called every simulation step)

Parameters
modelPointer to the MuJoCo model
dataPointer to the MuJoCo data
Note
This method will be called at the end of the mujoco_ros2_control read loop, before the update loop of controllers and the write loop. This means that changes to the data here will be visible to controllers and will affect the next simulation step.
This method will be called in a real-time thread, so it should avoid blocking operations and should be efficient.

Implemented in mujoco_ros2_control_plugins::HeartbeatPublisherPlugin.


The documentation for this class was generated from the following file: