717 lines
23 KiB
XML
717 lines
23 KiB
XML
<robot name="robot">
|
|
<link name="base_footprint"></link>
|
|
<joint name="base_joint" type="fixed">
|
|
<parent link="base_footprint" />
|
|
<child link="base_link" />
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
<link name="base_link">
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.1 0.05 0.05" />
|
|
</geometry>
|
|
<material name="base_link-material">
|
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.1 0.05 0.05" />
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<mass value="1" />
|
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
</inertial>
|
|
</link>
|
|
<joint name="base_link_to_spine_1" type="revolute">
|
|
<parent link="base_link"/>
|
|
<child link="spine_1"/>
|
|
<origin xyz="0 0 0.0337" rpy="0 0 0"/>
|
|
<axis xyz="-0.9997 -0.0114 0.0229"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
<link name="spine_1">
|
|
<visual>
|
|
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.1 0.05 0.1" />
|
|
</geometry>
|
|
<material name="spine_1-material">
|
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.1 0.05 0.1" />
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
|
<mass value="1" />
|
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
</inertial>
|
|
</link>
|
|
<joint name="spine_1_to_upper_arm_right" type="revolute">
|
|
<parent link="spine_1"/>
|
|
<child link="upper_arm_right"/>
|
|
<origin xyz="0.0624 0 0.0973" rpy="-3.1416 -0.6587 0"/>
|
|
<axis xyz="-0.9997 -0.0114 0.0229"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
<link name="upper_arm_right">
|
|
<visual>
|
|
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.03 0.03 0.06" />
|
|
</geometry>
|
|
<material name="upper_arm_right-material">
|
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.03 0.03 0.06" />
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
|
<mass value="1" />
|
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
</inertial>
|
|
</link>
|
|
<joint name="upper_arm_right_to_lower_arm_right" type="revolute">
|
|
<parent link="upper_arm_right"/>
|
|
<child link="lower_arm_right"/>
|
|
<origin xyz="0.0 0 .065" rpy="0 0 0"/>
|
|
<axis xyz="-0.9997 -0.0114 0.0229"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
<link name="lower_arm_right">
|
|
<visual>
|
|
<origin xyz="0 0 0.025" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.03 0.03 0.05" />
|
|
</geometry>
|
|
<material name="lower_arm_right-material">
|
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0.025" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.03 0.03 0.05" />
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 0.025" rpy="0 0 0" />
|
|
<mass value="1" />
|
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
</inertial>
|
|
</link>
|
|
<joint name="lower_arm_right_to_hand_right" type="revolute">
|
|
<parent link="lower_arm_right"/>
|
|
<child link="hand_right"/>
|
|
<origin xyz="0 0 0.055" rpy="0 0 0"/>
|
|
<axis xyz="0 1 0"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
<link name="hand_right">
|
|
<visual>
|
|
<origin xyz="0 0 0.015" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.03 0.03 0.03" />
|
|
</geometry>
|
|
<material name="hand_right-material">
|
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0.015" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.03 0.03 0.03" />
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 0.015" rpy="0 0 0" />
|
|
<mass value="1" />
|
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
</inertial>
|
|
</link>
|
|
|
|
<!-- Left Upper Arm -->
|
|
<joint name="spine_1_to_upper_arm_left" type="revolute">
|
|
<parent link="spine_1"/>
|
|
<child link="upper_arm_left"/>
|
|
<origin xyz="-0.0624 0 0.0973" rpy="3.1416 0.6587 0"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
|
|
<link name="upper_arm_left">
|
|
<visual>
|
|
<origin xyz="0 0 0.03" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.03 0.03 0.06"/>
|
|
</geometry>
|
|
<material name="upper_arm_left-material">
|
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0.03" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.03 0.03 0.06"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 0.03" rpy="0 0 0"/>
|
|
<mass value="1"/>
|
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
|
|
<!-- Left Lower Arm -->
|
|
<joint name="upper_arm_left_to_lower_arm_left" type="revolute">
|
|
<parent link="upper_arm_left"/>
|
|
<child link="lower_arm_left"/>
|
|
<origin xyz="0.0 0 0.065" rpy="0 0 0"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
|
|
<link name="lower_arm_left">
|
|
<visual>
|
|
<origin xyz="0 0 0.025" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.03 0.03 0.05"/>
|
|
</geometry>
|
|
<material name="lower_arm_left-material">
|
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0.025" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.03 0.03 0.05"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 0.025" rpy="0 0 0"/>
|
|
<mass value="1"/>
|
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
|
|
<!-- Left Hand -->
|
|
<joint name="lower_arm_left_to_hand_left" type="revolute">
|
|
<parent link="lower_arm_left"/>
|
|
<child link="hand_left"/>
|
|
<origin xyz="0 0 0.055" rpy="0 0 0"/>
|
|
<axis xyz="0 1 0"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
|
|
|
|
<link name="hand_left">
|
|
<visual>
|
|
<origin xyz="0 0 0.015" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.03 0.03 0.03"/>
|
|
</geometry>
|
|
<material name="hand_left-material">
|
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0.015" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.03 0.03 0.03"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 0.015" rpy="0 0 0"/>
|
|
<mass value="1"/>
|
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
|
|
|
|
<joint name="base_link_to_upper_leg_right" type="revolute">
|
|
<parent link="base_link" />
|
|
<child link="upper_leg_right" />
|
|
<origin xyz="0.035 0 -0.035" rpy="0 0 0" />
|
|
<axis xyz="1 0 0"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/> </joint>
|
|
|
|
<link name="upper_leg_right">
|
|
<visual>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.04 0.07"/>
|
|
</geometry>
|
|
<material name="upper_leg_right-material">
|
|
<color rgba="0.0021 0.0497 0.4851 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.04 0.07"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<mass value="1"/>
|
|
<inertia ixx="0.1667" ixy="0" ixz="0" iyy="0.1667" iyz="0" izz="0.1667"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
|
|
<joint name="upper_leg_right_to_lower_leg_right" type="revolute">
|
|
<parent link="upper_leg_right"/>
|
|
<child link="lower_leg_right"/>
|
|
<origin xyz="0 0 -0.075" rpy="0 0 0"/>
|
|
<axis xyz="-0.9997 -0.0114 0.0229"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
|
|
|
|
<link name="lower_leg_right">
|
|
<visual>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.04 0.07"/>
|
|
</geometry>
|
|
<material name="lower_leg_right-material">
|
|
<color rgba="0.0021 0.0497 0.4851 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.04 0.07"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<mass value="1"/>
|
|
<inertia ixx="0.1667" ixy="0" ixz="0" iyy="0.1667" iyz="0" izz="0.1667"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
|
|
<joint name="lower_leg_right_to_foot_right" type="revolute">
|
|
<parent link="lower_leg_right"/>
|
|
<child link="foot_right"/>
|
|
<origin xyz="0 0 -0.075" rpy="0 0 0"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
|
|
<link name="foot_right">
|
|
<visual>
|
|
<origin xyz="0 0.02 -0.01" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.08 0.02"/>
|
|
</geometry>
|
|
<material name="foot_right-material">
|
|
<color rgba="0.0021 0.0497 0.4851 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0.02 -0.01" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.08 0.02"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0.02 -0.01" rpy="0 0 0"/>
|
|
<mass value="1"/>
|
|
<inertia ixx="0.1667" ixy="0" ixz="0" iyy="0.1667" iyz="0" izz="0.1667"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
|
|
|
|
|
|
<!-- Left Upper Leg -->
|
|
<joint name="base_link_to_upper_leg_left" type="revolute">
|
|
<parent link="base_link"/>
|
|
<child link="upper_leg_left"/>
|
|
<origin xyz="-0.035 0 -0.035" rpy="0 0 0"/>
|
|
<axis xyz="1 0 0"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
|
|
<link name="upper_leg_left">
|
|
<visual>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.04 0.07"/>
|
|
</geometry>
|
|
<material name="upper_leg_left-material">
|
|
<color rgba="0.0021 0.0497 0.4851 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.04 0.07"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<mass value="1"/>
|
|
<inertia ixx="0.1667" ixy="0" ixz="0" iyy="0.1667" iyz="0" izz="0.1667"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
|
|
<!-- Left Lower Leg -->
|
|
<joint name="upper_leg_left_to_lower_leg_left" type="revolute">
|
|
<parent link="upper_leg_left"/>
|
|
<child link="lower_leg_left"/>
|
|
<origin xyz="0 0 -0.075" rpy="0 0 0"/>
|
|
<axis xyz="-0.9997 -0.0114 0.0229"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
|
|
<link name="lower_leg_left">
|
|
<visual>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.04 0.07"/>
|
|
</geometry>
|
|
<material name="lower_leg_left-material">
|
|
<color rgba="0.0021 0.0497 0.4851 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.04 0.07"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 -0.035" rpy="0 0 0"/>
|
|
<mass value="1"/>
|
|
<inertia ixx="0.1667" ixy="0" ixz="0" iyy="0.1667" iyz="0" izz="0.1667"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
|
|
<!-- Left Foot -->
|
|
<joint name="lower_leg_left_to_foot_left" type="revolute">
|
|
<parent link="lower_leg_left"/>
|
|
<child link="foot_left"/>
|
|
<origin xyz="0 0 -0.075" rpy="0 0 0"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
|
|
<link name="foot_left">
|
|
<visual>
|
|
<origin xyz="0 0.02 -0.01" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.08 0.02"/>
|
|
</geometry>
|
|
<material name="foot_left-material">
|
|
<color rgba="0.0021 0.0497 0.4851 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0.02 -0.01" rpy="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.04 0.08 0.02"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0.02 -0.01" rpy="0 0 0"/>
|
|
<mass value="1"/>
|
|
<inertia ixx="0.1667" ixy="0" ixz="0" iyy="0.1667" iyz="0" izz="0.1667"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
|
|
<joint name="spine_1_to_neck" type="revolute">
|
|
<parent link="spine_1"/>
|
|
<child link="neck"/>
|
|
<origin xyz="0 0 0.12" rpy="0 0 0"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
|
|
<link name="neck">
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.03 0.03 0.03" />
|
|
</geometry>
|
|
<material name="neck-material">
|
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.03 0.03 0.03" />
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<mass value="1" />
|
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
</inertial>
|
|
</link>
|
|
|
|
<joint name="neck_to_head" type="revolute">
|
|
<parent link="neck"/>
|
|
<child link="head"/>
|
|
<origin xyz="0 0 0.04" rpy="0 0 0"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="1000.0" lower="-1" upper="1" velocity="0.5"/>
|
|
</joint>
|
|
|
|
<link name="head">
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.06 0.06 0.06" />
|
|
</geometry>
|
|
<material name="head-material">
|
|
<color rgba="0.0021246888847058823 0.04970656597728775 0.48514994004665124 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<box size="0.06 0.06 0.06" />
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<mass value="1" />
|
|
<inertia ixx="0.16666666666666666" ixy="0" ixz="0" iyy="0.16666666666666666" iyz="0" izz="0.16666666666666666" />
|
|
</inertial>
|
|
</link>
|
|
|
|
|
|
<transmission name="spine_1_trans">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="base_link_to_spine_1">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="spine_motor_1">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="upper_arm_left">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="spine_1_to_upper_arm_left">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="spine_motor_1">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="lower_arm_left">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="upper_arm_left_to_lower_arm_left">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="spine_motor_1">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="hand_left">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="lower_arm_left_to_hand_left">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="spine_motor_1">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="upper_arm_right">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="spine_1_to_upper_arm_right">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="spine_motor_1">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="lower_arm_right">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="upper_arm_right_to_lower_arm_right">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="spine_motor_1">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="hand_right">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="lower_arm_right_to_hand_right">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="spine_motor_1">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="upper_leg_right">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="base_link_to_upper_leg_right">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="upper_leg_motor_right">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="lower_leg_right">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="upper_leg_right_to_lower_leg_right">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="lower_leg_motor_right">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="foot_right">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="lower_leg_right_to_foot_right">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="foot_motor_right">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="upper_leg_left">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="base_link_to_upper_leg_left">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="upper_leg_motor_left">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="lower_leg_left">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="upper_leg_left_to_lower_leg_left">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="lower_leg_motor_left">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="foot_left">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="lower_leg_left_to_foot_left">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="foot_motor_left">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="neck_base">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="spine_1_to_neck">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="neck_motor_base">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
<transmission name="neck_tip">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="neck_to_head">
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="neck_motor_tip">
|
|
<mechanicalReduction>22.75</mechanicalReduction>
|
|
<hardwareInterface>PositionJointInterface</hardwareInterface>
|
|
<encoderTicks>4096</encoderTicks>
|
|
<encoderValidMin>200</encoderValidMin>
|
|
<encoderValidMax>3500</encoderValidMax>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
</robot> |