Plugin to send a command to an actuator via ROS topic.
More...
#include <ActuatorCommand.h>
Plugin to send a command to an actuator via ROS topic.
Definition at line 19 of file ActuatorCommand.h.
◆ ActuatorCommand() [1/2]
◆ ActuatorCommand() [2/2]
MujocoRosUtils::ActuatorCommand::ActuatorCommand |
( |
const mjModel * |
m, |
|
|
mjData * |
d, |
|
|
int |
actuator_id, |
|
|
std::string |
topic_name |
|
) |
| |
|
protected |
Constructor.
- Parameters
-
m | model |
d | data |
actuator_id | actuator ID |
topic_name | topic name |
Definition at line 106 of file ActuatorCommand.cpp.
◆ callback()
void MujocoRosUtils::ActuatorCommand::callback |
( |
const std_msgs::Float64::ConstPtr & |
msg | ) |
|
|
protected |
◆ compute()
void MujocoRosUtils::ActuatorCommand::compute |
( |
const mjModel * |
m, |
|
|
mjData * |
d, |
|
|
int |
plugin_id |
|
) |
| |
◆ Create()
ActuatorCommand * MujocoRosUtils::ActuatorCommand::Create |
( |
const mjModel * |
m, |
|
|
mjData * |
d, |
|
|
int |
plugin_id |
|
) |
| |
|
static |
Create an instance.
- Parameters
-
m | model |
d | data |
plugin_id | plugin ID |
Definition at line 70 of file ActuatorCommand.cpp.
◆ RegisterPlugin()
MujocoRosUtils::ActuatorCommand::RegisterPlugin |
( |
| ) |
|
|
static |
◆ reset()
void MujocoRosUtils::ActuatorCommand::reset |
( |
const mjModel * |
m, |
|
|
int |
plugin_id |
|
) |
| |
◆ actuator_id_
int MujocoRosUtils::ActuatorCommand::actuator_id_ = -1 |
|
protected |
◆ callbackQueue_
ros::CallbackQueue MujocoRosUtils::ActuatorCommand::callbackQueue_ |
|
protected |
◆ ctrl_
mjtNum MujocoRosUtils::ActuatorCommand::ctrl_ = std::numeric_limits<mjtNum>::quiet_NaN() |
|
protected |
◆ nh_
std::shared_ptr<ros::NodeHandle> MujocoRosUtils::ActuatorCommand::nh_ |
|
protected |
◆ sub_
ros::Subscriber MujocoRosUtils::ActuatorCommand::sub_ |
|
protected |
The documentation for this class was generated from the following files:
- /home/runner/work/MujocoRosUtils/MujocoRosUtils/catkin_ws/src/isri-aist/MujocoRosUtils/plugin/ActuatorCommand.h
- /home/runner/work/MujocoRosUtils/MujocoRosUtils/catkin_ws/src/isri-aist/MujocoRosUtils/plugin/ActuatorCommand.cpp
- /home/runner/work/MujocoRosUtils/MujocoRosUtils/catkin_ws/src/isri-aist/MujocoRosUtils/plugin/Plugin.cpp