mujoco_ros_utils
ActuatorCommand.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <rclcpp/rclcpp.hpp>
4 #include <std_msgs/msg/float64.hpp>
5 
6 #include <mujoco/mjdata.h>
7 #include <mujoco/mjmodel.h>
8 #include <mujoco/mjtnum.h>
9 #include <mujoco/mjvisualize.h>
10 
11 #include <limits>
12 #include <string>
13 
14 namespace MujocoRosUtils
15 {
16 
19 {
20 public:
22  static void RegisterPlugin();
23 
29  static ActuatorCommand * Create(const mjModel * m, mjData * d, int plugin_id);
30 
31 public:
34 
39  void reset(const mjModel * m, int plugin_id);
40 
46  void compute(const mjModel * m, mjData * d, int plugin_id);
47 
48 protected:
55  ActuatorCommand(const mjModel * m, mjData * d, int actuator_id, std::string topic_name);
56 
60  void callback(const std_msgs::msg::Float64::SharedPtr msg);
61 
62 protected:
64  int actuator_id_ = -1;
65 
67  mjtNum ctrl_ = std::numeric_limits<mjtNum>::quiet_NaN();
68 
71  rclcpp::Node::SharedPtr nh_;
72  rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
73  rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr sub_;
75 };
76 
77 } // namespace MujocoRosUtils
Plugin to send a command to an actuator via ROS topic.
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.