Created
July 22, 2013 16:58
-
-
Save anonymous/6055562 to your computer and use it in GitHub Desktop.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0"?> | |
<robot name="orbit"> | |
<!--Torso Robot--> | |
<link name="orbit_torso"> | |
<inertial> | |
<mass value="11.83033"/> | |
<origin xyz="0.0 0.0 0.09538" rpy="0 0 0"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_torso.dae" scale="1.0 1.0 1.0" /> | |
</geometry> | |
</visual> | |
<collision> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_torso.dae" scale="1.0 1.0 1.0" /> | |
</geometry> | |
</collision> | |
</link> | |
<!--Leg Left Robot--> | |
<link name="orbit_hip_left"> | |
<inertial> | |
<mass value="0.65"/> | |
<origin xyz="0.0 0.0 -0.07721" rpy="0 0 0"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0.0 0.0 1.570795" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_hip_left.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</visual> | |
<collision> | |
<origin rpy="0.0 0.0 1.570795" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_hip_left.dae" scale="1.0 1.0 1.0" /> | |
</geometry> | |
</collision> | |
</link> | |
<link name="orbit_upperleg_left"> | |
<inertial> | |
<mass value="2.947251"/> | |
<origin xyz="0.0 0.0 -0.14543" rpy="0 0 0"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_upperleg_left.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</visual> | |
<collision> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_upperleg_left.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</collision> | |
</link> | |
<link name="orbit_lowerleg_left"> | |
<inertial> | |
<mass value="1.622083"/> | |
<origin xyz="0.0 0.0 -0.12544" rpy="0 0 0"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_lowerleg_left.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</visual> | |
<collision> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_lowerleg_left.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</collision> | |
</link> | |
<link name="orbit_foot_left"> | |
<inertial> | |
<mass value="1.256634"/> | |
<origin xyz="0.0 0.0 -0.04730" rpy="0 0 0"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_foot_left.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</visual> | |
<collision> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_foot_left.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</collision> | |
</link> | |
<!--Leg Right Robot--> | |
<link name="orbit_hip_right"> | |
<inertial> | |
<mass value="0.845221"/> | |
<origin xyz="0.0 0.0 -0.07721" rpy="0 0 0"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0.0 0.0 1.570795" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_hip_right.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</visual> | |
<collision> | |
<origin rpy="0.0 0.0 1.570795" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_hip_right.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</collision> | |
</link> | |
<link name="orbit_upperleg_right"> | |
<inertial> | |
<mass value="2.947251"/> | |
<origin xyz="0.0 0.0 -0.14543" rpy="0 0 0"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_upperleg_right.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</visual> | |
<collision> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_upperleg_right.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</collision> | |
</link> | |
<link name="orbit_lowerleg_right"> | |
<inertial> | |
<mass value="1.622083"/> | |
<origin xyz="0.0 0.0 -0.12544" rpy="0 0 0"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_lowerleg_right.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</visual> | |
<collision> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_lowerleg_right.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</collision> | |
</link> | |
<link name="orbit_foot_right"> | |
<inertial> | |
<mass value="1.256634"/> | |
<origin xyz="0.0 0.0 -0.04730" rpy="0 0 0"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_foot_right.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</visual> | |
<collision> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://orbit_description/meshes/orbit_foot_right.dae" scale="1.0 1.0 1.0"/> | |
</geometry> | |
</collision> | |
</link> | |
<!--Joint Robot--> | |
<joint name="Left_hip_yaw" type="revolute"> | |
<parent link="orbit_torso"/> | |
<child link="orbit_hip_left"/> | |
<origin rpy="0.0 0.0 1.570795" xyz="0.08977 -0.02000 0"/> | |
<axis xyz="0 0 1"/> | |
<!--<dynamics damping="0.1" friction="0" />--> | |
<limit effort="124.016" velocity="12" lower="-0.26" upper="0.26" /> | |
<!--<safety_controller k_position="100" k_velocity="100" soft_lower_limit="-10.6109" soft_upper_limit="10.6109" />--> | |
</joint> | |
<joint name="Left_hip_pitch" type="revolute"> | |
<parent link="orbit_hip_left"/> | |
<child link="orbit_upperleg_left"/> | |
<origin rpy="0.0 0.0 0.0" xyz="0 -0.01085 -0.11060"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="124.016" velocity="12" lower="-0.52" upper="1.71" /> | |
</joint> | |
<joint name="Left_knee_pitch" type="revolute"> | |
<parent link="orbit_upperleg_left"/> | |
<child link="orbit_lowerleg_left"/> | |
<origin rpy="0.0 0.0 0.0" xyz="0 -0.01085 -0.32000"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="124.016" velocity="12" lower="-2.25" upper="0.05" /> | |
</joint> | |
<joint name="Left_ankle_pitch" type="revolute"> | |
<parent link="orbit_lowerleg_left"/> | |
<child link="orbit_foot_left"/> | |
<origin rpy="0.0 0.0 0.0" xyz="0 -0.01085 -0.27700"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="124.016" velocity="12" lower="-0.79" upper="0.52" /> | |
</joint> | |
<joint name="Right_hip_yaw" type="revolute"> | |
<parent link="orbit_torso"/> | |
<child link="orbit_hip_right"/> | |
<origin rpy="0.0 0.0 1.570795" xyz="-0.08977 -0.02000 0"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="124.016" velocity="12" lower="-0.26" upper="0.26" /> | |
</joint> | |
<joint name="Right_hip_pitch" type="revolute"> | |
<parent link="orbit_hip_right"/> | |
<child link="orbit_upperleg_right"/> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0.01085 -0.11010"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="124.016" velocity="12" lower="-0.52" upper="1.71" /> | |
</joint> | |
<joint name="Right_knee_pitch" type="revolute"> | |
<parent link="orbit_upperleg_right"/> | |
<child link="orbit_lowerleg_right"/> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0.01085 -0.32000"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="124.016" velocity="12" lower="-2.25" upper="0.05" /> | |
</joint> | |
<joint name="Right_ankle_pitch" type="revolute"> | |
<parent link="orbit_lowerleg_right"/> | |
<child link="orbit_foot_right"/> | |
<origin rpy="0.0 0.0 0.0" xyz="0 0.01085 -0.27700"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="124.016" velocity="12" lower="-0.79" upper="0.52" /> | |
</joint> | |
<!--Transmission Robot--> | |
<transmission name="Left_hip_yaw_trans" type="pr2_mechanism_model/SimpleTransmission"> | |
<joint name="Left_hip_yaw" /> | |
<actuator name="Left_hip_yaw_motor" /> | |
<mechanicalReduction>1</mechanicalReduction> | |
<motorTorqueConstant>1</motorTorqueConstant> | |
</transmission> | |
<transmission name="Left_hip_pitch_trans" type="pr2_mechanism_model/SimpleTransmission"> | |
<joint name="Left_hip_pitch" /> | |
<actuator name="Left_hip_pitch_motor" /> | |
<mechanicalReduction>1</mechanicalReduction> | |
<motorTorqueConstant>1</motorTorqueConstant> | |
</transmission> | |
<transmission name="Left_knee_pitch_trans" type="pr2_mechanism_model/SimpleTransmission"> | |
<joint name="Left_knee_pitch" /> | |
<actuator name="Left_knee_pitch_motor" /> | |
<mechanicalReduction>1</mechanicalReduction> | |
<motorTorqueConstant>1</motorTorqueConstant> | |
</transmission> | |
<transmission name="Left_ankle_pitch_trans" type="pr2_mechanism_model/SimpleTransmission"> | |
<joint name="Left_ankle_pitch" /> | |
<actuator name="Left_ankle_pitch_motor" /> | |
<mechanicalReduction>1</mechanicalReduction> | |
<motorTorqueConstant>1</motorTorqueConstant> | |
</transmission> | |
<transmission name="Right_hip_yaw_trans" type="pr2_mechanism_model/SimpleTransmission"> | |
<joint name="Right_hip_yaw" /> | |
<actuator name="Right_hip_yaw_motor" /> | |
<mechanicalReduction>1</mechanicalReduction> | |
<motorTorqueConstant>1</motorTorqueConstant> | |
</transmission> | |
<transmission name="Right_hip_pitch_trans" type="pr2_mechanism_model/SimpleTransmission"> | |
<joint name="Right_hip_pitch" /> | |
<actuator name="Right_hip_pitch_motor" /> | |
<mechanicalReduction>1</mechanicalReduction> | |
<motorTorqueConstant>1</motorTorqueConstant> | |
</transmission> | |
<transmission name="Right_knee_pitch_trans" type="pr2_mechanism_model/SimpleTransmission"> | |
<joint name="Right_knee_pitch" /> | |
<actuator name="Right_knee_pitch_motor" /> | |
<mechanicalReduction>1</mechanicalReduction> | |
<motorTorqueConstant>1</motorTorqueConstant> | |
</transmission> | |
<transmission name="Right_ankle_pitch_trans" type="pr2_mechanism_model/SimpleTransmission"> | |
<joint name="Right_ankle_pitch" /> | |
<actuator name="Right_ankle_pitch_motor" /> | |
<mechanicalReduction>1</mechanicalReduction> | |
<motorTorqueConstant>1</motorTorqueConstant> | |
</transmission> | |
<!--Config Gazebo--> | |
<gazebo reference="orbit_torso"> | |
<material>Gazebo/White</material> | |
<turnGravityOff>false</turnGravityOff> | |
<selfCollide>true</selfCollide> | |
<!-- <dampingFactor>0.01</dampingFactor> --> | |
</gazebo> | |
<gazebo reference="orbit_hip_left"> | |
<material>Gazebo/White</material> | |
<turnGravityOff>false</turnGravityOff> | |
<selfCollide>true</selfCollide> | |
</gazebo> | |
<gazebo reference="orbit_upperleg_left"> | |
<material>Gazebo/White</material> | |
<turnGravityOff>false</turnGravityOff> | |
<selfCollide>true</selfCollide> | |
</gazebo> | |
<gazebo reference="orbit_lowerleg_left"> | |
<material>Gazebo/White</material> | |
<turnGravityOff>false</turnGravityOff> | |
<selfCollide>true</selfCollide> | |
</gazebo> | |
<gazebo reference="orbit_foot_left"> | |
<material>Gazebo/White</material> | |
<turnGravityOff>false</turnGravityOff> | |
<selfCollide>true</selfCollide> | |
</gazebo> | |
<gazebo reference="orbit_hip_right"> | |
<material>Gazebo/White</material> | |
<turnGravityOff>false</turnGravityOff> | |
<selfCollide>true</selfCollide> | |
</gazebo> | |
<gazebo reference="orbit_upperleg_right"> | |
<material>Gazebo/White</material> | |
<turnGravityOff>false</turnGravityOff> | |
<selfCollide>true</selfCollide> | |
</gazebo> | |
<gazebo reference="orbit_lowerleg_right"> | |
<material>Gazebo/White</material> | |
<turnGravityOff>false</turnGravityOff> | |
<selfCollide>true</selfCollide> | |
</gazebo> | |
<gazebo reference="orbit_foot_right"> | |
<material>Gazebo/White</material> | |
<turnGravityOff>false</turnGravityOff> | |
<selfCollide>true</selfCollide> | |
</gazebo> | |
</robot> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment