Plugin to send a command to an actuator via ROS topic.
More...
#include <ActuatorCommand.h>
|
| ActuatorCommand (const mjModel *m, mjData *d, int actuator_id, std::string topic_name) |
| Constructor. More...
|
|
void | callback (const std_msgs::msg::Float64::SharedPtr msg) |
| Constructor. More...
|
|
|
int | actuator_id_ = -1 |
| Actuator ID. More...
|
|
mjtNum | ctrl_ = std::numeric_limits<mjtNum>::quiet_NaN() |
| Actuator command (NaN for no command) More...
|
|
|
rclcpp::Node::SharedPtr | nh_ |
|
rclcpp::executors::SingleThreadedExecutor::SharedPtr | executor_ |
|
rclcpp::Subscription< std_msgs::msg::Float64 >::SharedPtr | sub_ |
|
Plugin to send a command to an actuator via ROS topic.
Definition at line 18 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::msg::Float64::SharedPtr |
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 |
◆ ctrl_
mjtNum MujocoRosUtils::ActuatorCommand::ctrl_ = std::numeric_limits<mjtNum>::quiet_NaN() |
|
protected |
◆ executor_
rclcpp::executors::SingleThreadedExecutor::SharedPtr MujocoRosUtils::ActuatorCommand::executor_ |
|
protected |
◆ nh_
rclcpp::Node::SharedPtr MujocoRosUtils::ActuatorCommand::nh_ |
|
protected |
◆ sub_
rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr MujocoRosUtils::ActuatorCommand::sub_ |
|
protected |
The documentation for this class was generated from the following files:
- /home/runner/work/MujocoRosUtils/MujocoRosUtils/colcon_ws/src/isri-aist/MujocoRosUtils/plugin/ActuatorCommand.h
- /home/runner/work/MujocoRosUtils/MujocoRosUtils/colcon_ws/src/isri-aist/MujocoRosUtils/plugin/ActuatorCommand.cpp
- /home/runner/work/MujocoRosUtils/MujocoRosUtils/colcon_ws/src/isri-aist/MujocoRosUtils/plugin/Plugin.cpp