161 lines
4.9 KiB
Plaintext
161 lines
4.9 KiB
Plaintext
|
<?xml version="1.0"?>
|
||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||
|
|
||
|
<xacro:macro name="r6bot_ros2_control" params="name">
|
||
|
|
||
|
<ros2_control name="${name}" type="system">
|
||
|
|
||
|
<hardware>
|
||
|
<plugin>hardware_unitree_mujoco/HardwareUnitree</plugin>
|
||
|
</hardware>
|
||
|
|
||
|
<joint name="FR_hip_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="FR_thigh_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="FR_calf_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="FL_hip_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="FL_thigh_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="FL_calf_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="RR_hip_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="RR_thigh_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="RR_calf_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="RL_hip_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="RL_thigh_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
<joint name="RL_calf_joint">
|
||
|
<command_interface name="position"/>
|
||
|
<command_interface name="velocity"/>
|
||
|
<command_interface name="effort"/>
|
||
|
<command_interface name="kp"/>
|
||
|
<command_interface name="kd"/>
|
||
|
|
||
|
<state_interface name="position"/>
|
||
|
<state_interface name="velocity"/>
|
||
|
<state_interface name="effort"/>
|
||
|
</joint>
|
||
|
|
||
|
</ros2_control>
|
||
|
|
||
|
</xacro:macro>
|
||
|
|
||
|
</robot>
|