Struct MuJoCoActuatorData
Defined in File data.hpp
Struct Documentation
-
struct MuJoCoActuatorData
Wrapper for MuJoCo actuators and relevant ROS HW interface data.
- Param joint_name:
Name of the MuJoCo joint handled by the actuator.
- Param position_interface:
Data for position command/state interface.
- Param velocity_interface:
Data for velocity command/state interface.
- Param effort_interface:
Data for effort command/state interface.
- Param pos_pid:
Pointer to position PID controller if configured.
- Param vel_pid:
Pointer to velocity PID controller if configured.
- Param actuator_type:
Type of the MuJoCo actuator.
- Param mj_joint_type:
MuJoCo joint type as per mjModel->jnt_type.
- Param mj_pos_adr:
MuJoCo position address in mjData->qpos.
- Param mj_vel_adr:
MuJoCo velocity address in mjData->qvel.
- Param mj_actuator_id:
MuJoCo actuator id as per mjModel->actuator_id.
- Param is_position_control_enabled:
Boolean flag indicating if position control is enabled.
- Param is_position_pid_control_enabled:
Boolean flag indicating if position PID control is enabled.
- Param is_velocity_pid_control_enabled:
Boolean flag indicating if velocity PID control is enabled.
- Param is_velocity_control_enabled:
Boolean flag indicating if velocity control is enabled.
- Param is_effort_control_enabled:
Boolean flag indicating if effort control is enabled.
- Param has_pos_pid:
Boolean flag indicating if a position PID controller is configured.
- Param has_vel_pid:
Boolean flag indicating if a velocity PID controller is configured.
Public Functions
-
inline void copy_state_to_transmission()
-
inline void copy_command_from_transmission()
-
inline void copy_command_to_state()
Public Members
-
std::string joint_name = ""
-
InterfaceData position_interface = {hardware_interface::HW_IF_POSITION}
-
InterfaceData velocity_interface = {hardware_interface::HW_IF_VELOCITY}
-
InterfaceData effort_interface = {hardware_interface::HW_IF_EFFORT}
-
std::shared_ptr<control_toolbox::PidROS> pos_pid = {nullptr}
-
std::shared_ptr<control_toolbox::PidROS> vel_pid = {nullptr}
-
ActuatorType actuator_type = {ActuatorType::UNKNOWN}
-
int mj_joint_type = -1
-
int mj_pos_adr = -1
-
int mj_vel_adr = -1
-
int mj_actuator_id = -1
-
bool is_position_control_enabled = {false}
-
bool is_position_pid_control_enabled = {false}
-
bool is_velocity_pid_control_enabled = {false}
-
bool is_velocity_control_enabled = {false}
-
bool is_effort_control_enabled = {false}
-
bool has_pos_pid = {false}
-
bool has_vel_pid = {false}