Mass of motors was being tilted to the left, due to FL hip motor and RL hip motor having a mass of 1.095 and FR hip motor and BR hip motor having a mass of 0.241. This led to issues with the laikago tilting. May require further investigation to see if the laikago is at the proper center of mass!
478 lines
13 KiB
XML
478 lines
13 KiB
XML
<?xml version="1.0" ?>
|
|
<robot name="plane">
|
|
<link name="chassis">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0.03 0.043794"/>
|
|
<mass value="13.715"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0.043794"/>
|
|
<geometry>
|
|
|
|
<mesh filename="chassis.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="yellow">
|
|
<color rgba="0.95 0.75 0.05 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="-1.57 0 0" xyz="0 0 0.043794"/>
|
|
<geometry>
|
|
|
|
<mesh filename="chassis_vhacd_mod.obj" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
|
|
|
|
<link name="FR_hip_motor">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.02 0 0"/>
|
|
<mass value="1.095"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="green"/>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint name="FR_hip_motor_2_chassis_joint" type="continuous">
|
|
<axis xyz="0 0 -1"/>
|
|
<parent link="chassis"/>
|
|
<child link="FR_hip_motor"/>
|
|
<origin rpy="0 0 0" xyz="-0.0817145 0 0.242889"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
<link name="FR_upper_leg">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
|
|
<mass value="1.527"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="upper_leg_mirror.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="blue"/>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint name="FR_upper_leg_2_hip_motor_joint" type="continuous">
|
|
<axis xyz="1 0 0"/>
|
|
<parent link="FR_hip_motor"/>
|
|
<child link="FR_upper_leg"/>
|
|
<origin rpy="0 0 0" xyz="-0.053565 0 0"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
<link name="FR_lower_leg">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
|
|
<mass value="0.241"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
|
|
<geometry>
|
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="red"/>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
|
|
<geometry>
|
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint name="FR_lower_leg_2_upper_leg_joint" type="continuous">
|
|
<axis xyz="1 0 0"/>
|
|
<parent link="FR_upper_leg"/>
|
|
<child link="FR_lower_leg"/>
|
|
|
|
<origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
|
|
<link name="FL_hip_motor">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-.02 0 0"/>
|
|
<mass value="1.095"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="green">
|
|
<color rgba="0.23 0.73 0.33 1"/>
|
|
</material>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint name="FL_hip_motor_2_chassis_joint" type="continuous">
|
|
<axis xyz="0 0 1"/>
|
|
<parent link="chassis"/>
|
|
<child link="FL_hip_motor"/>
|
|
<origin rpy="0 0 0" xyz="0.0817145 0 0.242889"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
<link name="FL_upper_leg">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
|
|
<mass value="1.527"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
|
|
<mesh filename="upper_leg.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="blue">
|
|
<color rgba="0.28 0.52 0.93 1"/>
|
|
</material>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
|
|
<joint name="FL_upper_leg_2_hip_motor_joint" type="continuous">
|
|
<axis xyz="1 0 0"/>
|
|
<parent link="FL_hip_motor"/>
|
|
<child link="FL_upper_leg"/>
|
|
<origin rpy="0 0 0" xyz="0.055855 0 0"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
|
|
<link name="FL_lower_leg">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
|
|
<mass value="0.241"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="red">
|
|
<color rgba="0.85 0.19 0.21 1"/>
|
|
</material>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint name="FL_lower_leg_2_upper_leg_joint" type="continuous">
|
|
<axis xyz="1 0 0"/>
|
|
<parent link="FL_upper_leg"/>
|
|
<child link="FL_lower_leg"/>
|
|
<origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
|
|
|
|
|
|
|
|
|
|
<link name="RR_hip_motor">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.02 0 0"/>
|
|
<mass value="1.095"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="green"/>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint name="RR_hip_motor_2_chassis_joint" type="continuous">
|
|
<axis xyz="0 0 -1"/>
|
|
<parent link="chassis"/>
|
|
<child link="RR_hip_motor"/>
|
|
<origin rpy="0 0 0" xyz="-0.0817145 0 -0.194401"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
<link name="RR_upper_leg">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
|
|
<mass value="1.527"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="upper_leg_mirror.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="blue"/>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint name="RR_upper_leg_2_hip_motor_joint" type="continuous">
|
|
<axis xyz="1 0 0"/>
|
|
<parent link="RR_hip_motor"/>
|
|
<child link="RR_upper_leg"/>
|
|
<origin rpy="0 0 0" xyz="-0.053565 0 0"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
<link name="RR_lower_leg">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
|
|
<mass value="0.241"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="red"/>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint name="RR_lower_leg_2_upper_leg_joint" type="continuous">
|
|
<axis xyz="1 0 0"/>
|
|
<parent link="RR_upper_leg"/>
|
|
<child link="RR_lower_leg"/>
|
|
<origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
|
|
<link name="RL_hip_motor">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-.02 0 0"/>
|
|
<mass value="1.095"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="green"/>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint name="RL_hip_motor_2_chassis_joint" type="continuous">
|
|
<axis xyz="0 0 1"/>
|
|
<parent link="chassis"/>
|
|
<child link="RL_hip_motor"/>
|
|
|
|
<origin rpy="0 0 0" xyz="0.0817145 0 -0.194401"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
<link name="RL_upper_leg">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
|
|
<mass value="1.527"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="upper_leg.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="blue"/>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
|
|
<joint name="RL_upper_leg_2_hip_motor_joint" type="continuous">
|
|
<axis xyz="1 0 0"/>
|
|
<parent link="RL_hip_motor"/>
|
|
<child link="RL_upper_leg"/>
|
|
<origin rpy="0 0 0" xyz="0.055855 0 0"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
|
|
<link name="RL_lower_leg">
|
|
<contact>
|
|
<lateral_friction value="1"/>
|
|
</contact>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
|
|
<mass value="0.241"/>
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
<material name="red"/>
|
|
</visual>
|
|
|
|
<collision>
|
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
</link>
|
|
|
|
<joint name="RL_lower_leg_2_upper_leg_joint" type="continuous">
|
|
<axis xyz="1 0 0"/>
|
|
<parent link="RL_upper_leg"/>
|
|
<child link="RL_lower_leg"/>
|
|
<origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/>
|
|
<limit effort="100" velocity="100"/>
|
|
<joint_properties damping=".0" friction=".0"/>
|
|
</joint>
|
|
|
|
|
|
|
|
</robot>
|
|
|