3 #include <rclcpp/rclcpp.hpp>
4 #include <std_msgs/msg/float64.hpp>
6 #include <mujoco/mjdata.h>
7 #include <mujoco/mjmodel.h>
8 #include <mujoco/mjtnum.h>
9 #include <mujoco/mjvisualize.h>
39 void reset(
const mjModel * m,
int plugin_id);
46 void compute(
const mjModel * m, mjData * d,
int plugin_id);
55 ActuatorCommand(
const mjModel * m, mjData * d,
int actuator_id, std::string topic_name);
60 void callback(
const std_msgs::msg::Float64::SharedPtr msg);
67 mjtNum
ctrl_ = std::numeric_limits<mjtNum>::quiet_NaN();
71 rclcpp::Node::SharedPtr
nh_;
72 rclcpp::executors::SingleThreadedExecutor::SharedPtr
executor_;
73 rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr
sub_;
Plugin to send a command to an actuator via ROS topic.
int actuator_id_
Actuator ID.
static void RegisterPlugin()
Register plugin.
void reset(const mjModel *m, int plugin_id)
Reset.
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_
mjtNum ctrl_
Actuator command (NaN for no command)
rclcpp::Subscription< std_msgs::msg::Float64 >::SharedPtr sub_
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
ActuatorCommand(ActuatorCommand &&)=default
Copy constructor.
rclcpp::Node::SharedPtr nh_
void callback(const std_msgs::msg::Float64::SharedPtr msg)
Constructor.
static ActuatorCommand * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.