Struct URDFJointData
Defined in File data.hpp
Struct Documentation
-
struct URDFJointData
Structure for the URDF joint data.
- Param name:
Name of the joint.
- 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 command_interfaces:
Vector of command interface names supported by the joint.
- Param is_mimic:
Boolean flag indicating if the joint is a mimic joint.
- Param mimicked_joint_index:
Index of the joint being mimicked.
- Param mimic_multiplier:
Multiplier for the mimic joint.
- Param is_position_control_enabled:
Boolean flag indicating if position 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.
Public Functions
-
inline void copy_state_from_transmission()
-
inline void copy_command_to_transmission()
-
inline void copy_state_to_command()
Public Members
-
std::string 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::vector<std::string> command_interfaces = {}
-
bool is_mimic = {false}
-
int mimicked_joint_index
-
double mimic_multiplier
-
bool is_position_control_enabled = {false}
-
bool is_velocity_control_enabled = {false}
-
bool is_effort_control_enabled = {false}