mujoco_ros_utils
Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
MujocoRosUtils::ActuatorCommand Class Reference

Plugin to send a command to an actuator via ROS topic. More...

#include <ActuatorCommand.h>

Public Member Functions

 ActuatorCommand (ActuatorCommand &&)=default
 Copy constructor. More...
 
void reset (const mjModel *m, int plugin_id)
 Reset. More...
 
void compute (const mjModel *m, mjData *d, int plugin_id)
 Compute. More...
 

Static Public Member Functions

static void RegisterPlugin ()
 Register plugin. More...
 
static ActuatorCommandCreate (const mjModel *m, mjData *d, int plugin_id)
 Create an instance. More...
 

Protected Member Functions

 ActuatorCommand (const mjModel *m, mjData *d, int actuator_id, std::string topic_name)
 Constructor. More...
 
void callback (const std_msgs::Float64::ConstPtr &msg)
 Constructor. More...
 

Protected Attributes

int actuator_id_ = -1
 Actuator ID. More...
 
mjtNum ctrl_ = std::numeric_limits<mjtNum>::quiet_NaN()
 Actuator command (NaN for no command) More...
 
std::shared_ptr< ros::NodeHandle > nh_
 
ros::CallbackQueue callbackQueue_
 
ros::Subscriber sub_
 

Detailed Description

Plugin to send a command to an actuator via ROS topic.

Definition at line 19 of file ActuatorCommand.h.

Constructor & Destructor Documentation

◆ ActuatorCommand() [1/2]

MujocoRosUtils::ActuatorCommand::ActuatorCommand ( ActuatorCommand &&  )
default

Copy constructor.

◆ ActuatorCommand() [2/2]

MujocoRosUtils::ActuatorCommand::ActuatorCommand ( const mjModel *  m,
mjData *  d,
int  actuator_id,
std::string  topic_name 
)
protected

Constructor.

Parameters
mmodel
ddata
actuator_idactuator ID
topic_nametopic name

Definition at line 106 of file ActuatorCommand.cpp.

Member Function Documentation

◆ callback()

void MujocoRosUtils::ActuatorCommand::callback ( const std_msgs::Float64::ConstPtr &  msg)
protected

Constructor.

Parameters
msgcommand message

Definition at line 153 of file ActuatorCommand.cpp.

◆ compute()

void MujocoRosUtils::ActuatorCommand::compute ( const mjModel *  m,
mjData *  d,
int  plugin_id 
)

Compute.

Parameters
mmodel
ddata
plugin_idplugin ID

Definition at line 137 of file ActuatorCommand.cpp.

◆ Create()

ActuatorCommand * MujocoRosUtils::ActuatorCommand::Create ( const mjModel *  m,
mjData *  d,
int  plugin_id 
)
static

Create an instance.

Parameters
mmodel
ddata
plugin_idplugin ID

Definition at line 70 of file ActuatorCommand.cpp.

◆ RegisterPlugin()

MujocoRosUtils::ActuatorCommand::RegisterPlugin ( )
static

Register plugin.

Definition at line 10 of file ActuatorCommand.cpp.

◆ reset()

void MujocoRosUtils::ActuatorCommand::reset ( const mjModel *  m,
int  plugin_id 
)

Reset.

Parameters
mmodel
plugin_idplugin ID

Definition at line 131 of file ActuatorCommand.cpp.

Member Data Documentation

◆ actuator_id_

int MujocoRosUtils::ActuatorCommand::actuator_id_ = -1
protected

Actuator ID.

Definition at line 65 of file ActuatorCommand.h.

◆ callbackQueue_

ros::CallbackQueue MujocoRosUtils::ActuatorCommand::callbackQueue_
protected

ROS variables

Definition at line 73 of file ActuatorCommand.h.

◆ ctrl_

mjtNum MujocoRosUtils::ActuatorCommand::ctrl_ = std::numeric_limits<mjtNum>::quiet_NaN()
protected

Actuator command (NaN for no command)

Definition at line 68 of file ActuatorCommand.h.

◆ nh_

std::shared_ptr<ros::NodeHandle> MujocoRosUtils::ActuatorCommand::nh_
protected

ROS variables

Definition at line 72 of file ActuatorCommand.h.

◆ sub_

ros::Subscriber MujocoRosUtils::ActuatorCommand::sub_
protected

ROS variables

Definition at line 74 of file ActuatorCommand.h.


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