diff --git a/robots/anymal_b_simple_description/robots/anymal-kinova.urdf b/robots/anymal_b_simple_description/robots/anymal-kinova.urdf index 450422461c1a463d4cb6d8ffd652a775c71e72c3..2031152048a68c84e738b33e2315db79cea9fca6 100644 --- a/robots/anymal_b_simple_description/robots/anymal-kinova.urdf +++ b/robots/anymal_b_simple_description/robots/anymal-kinova.urdf @@ -1,10 +1,10 @@ <?xml version="1.0" ?> <!-- =================================================================================== --> -<!-- | This document was autogenerated by xacro from anymal.urdf.xacro | --> -<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> +<!-- | This URDF was edited to fix inertias. | --> <!-- =================================================================================== --> <!-- This file contains the description of the ANYmal B robot. --> -<robot name="anymal" xmlns:xacro="http://www.ros.org/wiki/xacro"> +<robot name="anymal" + xmlns:xacro="http://www.ros.org/wiki/xacro"> <material name="black"> <color rgba="0.0 0.0 0.0 1.0"/> </material> @@ -100,21 +100,26 @@ <box size="0.531 0.02 0.07"/> </geometry> </collision> + <inertial> + <origin rpy="0 0 0" xyz="-0.001960558279 -0.001413217745 0.050207125344"/> + <mass value="16.793507758"/> + <inertia ixx="0.217391101503" ixy="-0.00132873239126" ixz="-0.00228200226173" iyy="0.639432546734" iyz="-0.00138078263145" izz="0.62414077654"/> + </inertial> </link> <!-- Fixed joint to add dummy inertia link --> - <joint name="base_to_base_inertia" type="fixed"> + <!-- <joint name="base_to_base_inertia" type="fixed"> <parent link="base"/> <child link="base_inertia"/> <origin rpy="0 0 0" xyz="0 0 0"/> - </joint> + </joint> --> <!-- Dummy inertia link, because KDL cannot have inertia on the base link --> - <link name="base_inertia"> + <!-- <link name="base_inertia"> <inertial> <origin rpy="0 0 0" xyz="-0.001960558279 -0.001413217745 0.050207125344"/> <mass value="16.793507758"/> <inertia ixx="0.217391101503" ixy="-0.00132873239126" ixz="-0.00228200226173" iyy="0.639432546734" iyz="-0.00138078263145" izz="0.62414077654"/> </inertial> - </link> + </link> --> <!-- Xacro:Properties --> <!-- [kg * m^2] --> <!-- [A] --> @@ -278,6 +283,18 @@ <sphere radius="0.031"/> </geometry> </collision> + <inertial> + <mass value="0.001"/> + <inertia ixx="4.90e-07" ixy="0.0" ixz="0.0" iyy="4.90e-07" iyz="0.0" izz="4.90e-07"/> + <!-- for a sphere: 2/5 m * r**2 --> + </inertial> + <!-- Bullet specific parameters --> + <contact> + <lateral_friction value="1.0"/> + <stiffness value="300000"/> + <damping value="15000"/> + <!--<restitution value="0.5"/>--> + </contact> </link> <!-- Gazebo customization --> <gazebo reference="LF_FOOT"> @@ -449,6 +466,18 @@ <sphere radius="0.031"/> </geometry> </collision> + <inertial> + <mass value="0.001"/> + <inertia ixx="4.90e-07" ixy="0.0" ixz="0.0" iyy="4.90e-07" iyz="0.0" izz="4.90e-07"/> + <!-- for a sphere: 2/5 m * r**2 --> + </inertial> + <!-- Bullet specific parameters --> + <contact> + <lateral_friction value="1.0"/> + <stiffness value="300000"/> + <damping value="15000"/> + <!--<restitution value="0.5"/>--> + </contact> </link> <!-- Gazebo customization --> <gazebo reference="RF_FOOT"> @@ -620,6 +649,18 @@ <sphere radius="0.031"/> </geometry> </collision> + <inertial> + <mass value="0.001"/> + <inertia ixx="4.90e-07" ixy="0.0" ixz="0.0" iyy="4.90e-07" iyz="0.0" izz="4.90e-07"/> + <!-- for a sphere: 2/5 m * r**2 --> + </inertial> + <!-- Bullet specific parameters --> + <contact> + <lateral_friction value="1.0"/> + <stiffness value="300000"/> + <damping value="15000"/> + <!--<restitution value="0.5"/>--> + </contact> </link> <!-- Gazebo customization --> <gazebo reference="LH_FOOT"> @@ -791,6 +832,18 @@ <sphere radius="0.031"/> </geometry> </collision> + <inertial> + <mass value="0.001"/> + <inertia ixx="4.90e-07" ixy="0.0" ixz="0.0" iyy="4.90e-07" iyz="0.0" izz="4.90e-07"/> + <!-- for a sphere: 2/5 m * r**2 --> + </inertial> + <!-- Bullet specific parameters --> + <contact> + <lateral_friction value="1.0"/> + <stiffness value="300000"/> + <damping value="15000"/> + <!--<restitution value="0.5"/>--> + </contact> </link> <!-- Gazebo customization --> <gazebo reference="RH_FOOT"> @@ -825,475 +878,504 @@ <origin rpy="0 3.14159265359 0" xyz="0.038 0.06245 0.1837"/> </joint> - <link name="jaco_front_hatch_support_v2"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/jaco_front_hatch_support_v2.dae"/> - </geometry> - </visual> - </link> - <joint name="base_to_jaco_support" type="fixed"> - <parent link="base"/> - <child link="jaco_front_hatch_support_v2"/> - <origin rpy="0 0 0" xyz="0.2692 0.00 0.06713"/> - </joint> + <link name="jaco_front_hatch_support_v2"> + <!-- TODO: Proper inertia --> + <inertial> + <mass value="0.205"/> + <inertia ixx="4.90e-07" ixy="0.0" ixz="0.0" iyy="4.90e-07" iyz="0.0" izz="4.90e-07"/> + <!-- for a sphere: 2/5 m * r**2 --> + </inertial> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/jaco_front_hatch_support_v2.dae"/> + </geometry> + </visual> + <collision> + <origin xyz="0 0 0.02325"/> + <geometry> + <sphere radius="0.031"/> + </geometry> + </collision> + </link> + <joint name="base_to_jaco_support" type="fixed"> + <parent link="base"/> + <child link="jaco_front_hatch_support_v2"/> + <origin rpy="0 0 0" xyz="0.2692 0.00 0.06713"/> + </joint> - <link name="jaco_mounting_block"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/jaco_mounting_block.dae"/> - </geometry> - </visual> - </link> - <joint name="jaco_support_to_jaco_mounting_block" type="fixed"> - <parent link="jaco_front_hatch_support_v2"/> - <child link="jaco_mounting_block"/> - <origin rpy="0 0 0" xyz="0.045 0.00 -0.007626"/> - </joint> + <link name="jaco_mounting_block"> + <!-- TODO: Proper inertia --> + <inertial> + <mass value="0.1741"/><!-- Volume = 0.000064 m^3; aluminium density (alloy 6061) = 2720 kg/m^3 --> + <inertia ixx="4.90e-07" ixy="0.0" ixz="0.0" iyy="4.90e-07" iyz="0.0" izz="4.90e-07"/> + <!-- for a sphere: 2/5 m * r**2 --> + </inertial> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/jaco_mounting_block.dae"/> + </geometry> + </visual> + <collision> + <origin xyz="0 0 0.02325"/> + <geometry> + <sphere radius="0.031"/> + </geometry> + </collision> + </link> + <joint name="jaco_support_to_jaco_mounting_block" type="fixed"> + <parent link="jaco_front_hatch_support_v2"/> + <child link="jaco_mounting_block"/> + <origin rpy="0 0 0" xyz="0.045 0.00 -0.007626"/> + </joint> - <link name="j2s6s200_link_base"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/base.dae"/> - </geometry> - <material name="carbon_fiber"> - <color rgba="0.3 0.3 0.3 1"/> - </material> - </visual> - <collision> - <geometry> - <mesh filename="package://kinova_description/meshes/base.dae"/> - </geometry> - </collision> - <inertial> - <mass value="0.46784"/> - <origin rpy="0 0 0" xyz="0 0 0.1255"/> - <inertia ixx="0.000951270861568" ixy="0" ixz="0" iyy="0.000951270861568" iyz="0" izz="0.000374272"/> - </inertial> - </link> - <joint name="jaco_mounting_block_to_j2s6s200_link_base" type="fixed"> - <parent link="jaco_mounting_block"/> - <child link="j2s6s200_link_base"/> - <axis xyz="0 0 0"/> - <limit effort="0" lower="0" upper="0" velocity="0"/> - <origin rpy="0 0 1.57079632679" xyz="0.000 0.000 0.000"/> - <dynamics damping="0.0" friction="0.0"/> - </joint> - <link name="j2s6s200_link_1"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/shoulder.dae"/> - </geometry> - <material name="carbon_fiber"> - <color rgba="0.3 0.3 0.3 1"/> - </material> - </visual> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/ring_big.dae"/> - </geometry> - </visual> - <collision> - <geometry> - <mesh filename="package://kinova_description/meshes/shoulder.dae"/> - </geometry> - </collision> - <inertial> - <mass value="0.7477"/> - <origin xyz="0 -0.002 -0.0605"/> - <inertia ixx="0.00152031725204" ixy="0" ixz="0" iyy="0.00152031725204" iyz="0" izz="0.00059816"/> - </inertial> - </link> - <joint name="j2s6s200_joint_1" type="revolute"> - <parent link="j2s6s200_link_base"/> - <child link="j2s6s200_link_1"/> - <axis xyz="0 0 1"/> - <limit effort="40" lower="-6.28318530718" upper="6.28318530718" velocity="0.628318530718"/> - <origin rpy="0 3.14159265359 0" xyz="0 0 0.15675"/> - <dynamics damping="0.0" friction="0.0"/> - </joint> - <transmission name="j2s6s200_joint_1_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="j2s6s200_joint_1"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - </joint> - <actuator name="j2s6s200_joint_1_actuator"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - <mechanicalReduction>160</mechanicalReduction> - </actuator> - </transmission> - <link name="j2s6s200_link_2"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/arm.dae"/> - </geometry> - <material name="carbon_fiber"> - <color rgba="0.3 0.3 0.3 1"/> - </material> - </visual> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/ring_big.dae"/> - </geometry> - </visual> - <collision> - <geometry> - <mesh filename="package://kinova_description/meshes/arm.dae"/> - </geometry> - </collision> - <inertial> - <mass value="0.99"/> - <origin xyz="0 -0.2065 -0.01"/> - <inertia ixx="0.010502207991" ixy="0" ixz="0" iyy="0.000792" iyz="0" izz="0.010502207991"/> - </inertial> - </link> - <joint name="j2s6s200_joint_2" type="revolute"> - <parent link="j2s6s200_link_1"/> - <child link="j2s6s200_link_2"/> - <axis xyz="0 0 1"/> - <limit effort="80" lower="0.820304748437" upper="5.46288055874" velocity="0.628318530718"/> - <origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0.0016 -0.11875"/> - <dynamics damping="0.0" friction="0.0"/> + <link name="j2s6s200_link_base"> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/base.dae"/> + </geometry> + <material name="carbon_fiber"> + <color rgba="0.3 0.3 0.3 1"/> + </material> + </visual> + <collision> + <geometry> + <mesh filename="package://kinova_description/meshes/base.dae"/> + </geometry> + </collision> + <inertial> + <mass value="0.46784"/> + <origin rpy="0 0 0" xyz="0 0 0.1255"/> + <inertia ixx="0.000951270861568" ixy="0" ixz="0" iyy="0.000951270861568" iyz="0" izz="0.000374272"/> + </inertial> + </link> + <joint name="jaco_mounting_block_to_j2s6s200_link_base" type="fixed"> + <parent link="jaco_mounting_block"/> + <child link="j2s6s200_link_base"/> + <axis xyz="0 0 0"/> + <limit effort="0" lower="0" upper="0" velocity="0"/> + <origin rpy="0 0 1.57079632679" xyz="0.000 0.000 0.000"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <link name="j2s6s200_link_1"> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/shoulder.dae"/> + </geometry> + <material name="carbon_fiber"> + <color rgba="0.3 0.3 0.3 1"/> + </material> + </visual> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/ring_big.dae"/> + </geometry> + </visual> + <collision> + <geometry> + <mesh filename="package://kinova_description/meshes/shoulder.dae"/> + </geometry> + </collision> + <inertial> + <mass value="0.7477"/> + <origin xyz="0 -0.002 -0.0605"/> + <inertia ixx="0.00152031725204" ixy="0" ixz="0" iyy="0.00152031725204" iyz="0" izz="0.00059816"/> + </inertial> + </link> + <joint name="j2s6s200_joint_1" type="revolute"><!-- continuous --> + <parent link="j2s6s200_link_base"/> + <child link="j2s6s200_link_1"/> + <axis xyz="0 0 1"/> + <limit effort="40" lower="-6.28318530718" upper="6.28318530718" velocity="0.628318530718"/> + <origin rpy="0 3.14159265359 0" xyz="0 0 0.15675"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <transmission name="j2s6s200_joint_1_trans"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="j2s6s200_joint_1"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> - <transmission name="j2s6s200_joint_2_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="j2s6s200_joint_2"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - </joint> - <actuator name="j2s6s200_joint_2_actuator"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - <mechanicalReduction>160</mechanicalReduction> - </actuator> - </transmission> - <link name="j2s6s200_link_3"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/forearm.dae"/> - </geometry> - <material name="carbon_fiber"> - <color rgba="0.3 0.3 0.3 1"/> - </material> - </visual> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/ring_big.dae"/> - </geometry> - </visual> - <collision> - <geometry> - <mesh filename="package://kinova_description/meshes/forearm.dae"/> - </geometry> - </collision> - <inertial> - <mass value="0.6763"/> - <origin xyz="0 0.081 -0.0086"/> - <inertia ixx="0.00142022431908" ixy="0" ixz="0" iyy="0.000304335" iyz="0" izz="0.00142022431908"/> - </inertial> - </link> - <joint name="j2s6s200_joint_3" type="revolute"> - <parent link="j2s6s200_link_2"/> - <child link="j2s6s200_link_3"/> - <axis xyz="0 0 1"/> - <limit effort="40" lower="0.331612557879" upper="5.9515727493" velocity="0.628318530718"/> - <origin rpy="0 3.14159265359 0" xyz="0 -0.410 0"/> - <dynamics damping="0.0" friction="0.0"/> + <actuator name="j2s6s200_joint_1_actuator"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>160</mechanicalReduction> + </actuator> + </transmission> + <link name="j2s6s200_link_2"> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/arm.dae"/> + </geometry> + <material name="carbon_fiber"> + <color rgba="0.3 0.3 0.3 1"/> + </material> + </visual> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/ring_big.dae"/> + </geometry> + </visual> + <collision> + <geometry> + <mesh filename="package://kinova_description/meshes/arm.dae"/> + </geometry> + </collision> + <inertial> + <mass value="0.99"/> + <origin xyz="0 -0.2065 -0.01"/> + <inertia ixx="0.010502207991" ixy="0" ixz="0" iyy="0.000792" iyz="0" izz="0.010502207991"/> + </inertial> + </link> + <joint name="j2s6s200_joint_2" type="revolute"> + <parent link="j2s6s200_link_1"/> + <child link="j2s6s200_link_2"/> + <axis xyz="0 0 1"/> + <limit effort="80" lower="0.820304748437" upper="5.46288055874" velocity="0.628318530718"/> + <origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0.0016 -0.11875"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <transmission name="j2s6s200_joint_2_trans"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="j2s6s200_joint_2"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> - <transmission name="j2s6s200_joint_3_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="j2s6s200_joint_3"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - </joint> - <actuator name="j2s6s200_joint_3_actuator"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - <mechanicalReduction>160</mechanicalReduction> - </actuator> - </transmission> - <link name="j2s6s200_link_4"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/wrist_spherical_1.dae"/> - </geometry> - <material name="carbon_fiber"> - <color rgba="0.3 0.3 0.3 1"/> - </material> - </visual> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/ring_small.dae"/> - </geometry> - </visual> - <collision> - <geometry> - <mesh filename="package://kinova_description/meshes/wrist_spherical_1.dae"/> - </geometry> - </collision> - <inertial> - <mass value="0.463"/> - <origin xyz="0 0.0028848942 -0.0541932613"/> - <inertia ixx="0.0004321316048" ixy="0" ixz="0" iyy="0.0004321316048" iyz="0" izz="9.26e-05"/> - </inertial> - </link> - <joint name="j2s6s200_joint_4" type="revolute"> - <parent link="j2s6s200_link_3"/> - <child link="j2s6s200_link_4"/> - <axis xyz="0 0 1"/> - <limit effort="20" lower="-6.28318530718" upper="6.28318530718" velocity="0.837758040957"/> - <origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0.2073 -0.0114"/> - <dynamics damping="0.0" friction="0.0"/> + <actuator name="j2s6s200_joint_2_actuator"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>160</mechanicalReduction> + </actuator> + </transmission> + <link name="j2s6s200_link_3"> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/forearm.dae"/> + </geometry> + <material name="carbon_fiber"> + <color rgba="0.3 0.3 0.3 1"/> + </material> + </visual> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/ring_big.dae"/> + </geometry> + </visual> + <collision> + <geometry> + <mesh filename="package://kinova_description/meshes/forearm.dae"/> + </geometry> + </collision> + <inertial> + <mass value="0.6763"/> + <origin xyz="0 0.081 -0.0086"/> + <inertia ixx="0.00142022431908" ixy="0" ixz="0" iyy="0.000304335" iyz="0" izz="0.00142022431908"/> + </inertial> + </link> + <joint name="j2s6s200_joint_3" type="revolute"> + <parent link="j2s6s200_link_2"/> + <child link="j2s6s200_link_3"/> + <axis xyz="0 0 1"/> + <limit effort="40" lower="0.331612557879" upper="5.9515727493" velocity="0.628318530718"/> + <origin rpy="0 3.14159265359 0" xyz="0 -0.410 0"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <transmission name="j2s6s200_joint_3_trans"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="j2s6s200_joint_3"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> - <transmission name="j2s6s200_joint_4_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="j2s6s200_joint_4"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - </joint> - <actuator name="j2s6s200_joint_4_actuator"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - <mechanicalReduction>160</mechanicalReduction> - </actuator> - </transmission> - <link name="j2s6s200_link_5"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/wrist_spherical_2.dae"/> - </geometry> - <material name="carbon_fiber"> - <color rgba="0.3 0.3 0.3 1"/> - </material> - </visual> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/ring_small.dae"/> - </geometry> - </visual> - <collision> - <geometry> - <mesh filename="package://kinova_description/meshes/wrist_spherical_2.dae"/> - </geometry> - </collision> - <inertial> - <mass value="0.463"/> - <origin xyz="0 0.0497208855 -0.0028562765"/> - <inertia ixx="0.0004321316048" ixy="0" ixz="0" iyy="9.26e-05" iyz="0" izz="0.0004321316048"/> - </inertial> - </link> - <joint name="j2s6s200_joint_5" type="revolute"> - <parent link="j2s6s200_link_4"/> - <child link="j2s6s200_link_5"/> - <axis xyz="0 0 1"/> - <limit effort="20" lower="0.523598775598" upper="5.75958653158" velocity="0.837758040957"/> - <origin rpy="1.57079632679 0 3.14159265359" xyz="0 0 -0.10375"/> - <dynamics damping="0.0" friction="0.0"/> + <actuator name="j2s6s200_joint_3_actuator"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>160</mechanicalReduction> + </actuator> + </transmission> + <link name="j2s6s200_link_4"> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/wrist_spherical_1.dae"/> + </geometry> + <material name="carbon_fiber"> + <color rgba="0.3 0.3 0.3 1"/> + </material> + </visual> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/ring_small.dae"/> + </geometry> + </visual> + <collision> + <geometry> + <mesh filename="package://kinova_description/meshes/wrist_spherical_1.dae"/> + </geometry> + </collision> + <inertial> + <mass value="0.463"/> + <origin xyz="0 0.0028848942 -0.0541932613"/> + <inertia ixx="0.0004321316048" ixy="0" ixz="0" iyy="0.0004321316048" iyz="0" izz="9.26e-05"/> + </inertial> + </link> + <joint name="j2s6s200_joint_4" type="revolute"><!-- continuous --> + <parent link="j2s6s200_link_3"/> + <child link="j2s6s200_link_4"/> + <axis xyz="0 0 1"/> + <limit effort="20" lower="-6.28318530718" upper="6.28318530718" velocity="0.837758040957"/> + <origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0.2073 -0.0114"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <transmission name="j2s6s200_joint_4_trans"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="j2s6s200_joint_4"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> - <transmission name="j2s6s200_joint_5_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="j2s6s200_joint_5"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - </joint> - <actuator name="j2s6s200_joint_5_actuator"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - <mechanicalReduction>160</mechanicalReduction> - </actuator> - </transmission> - <link name="j2s6s200_link_6"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/hand_2finger.dae"/> - </geometry> - <material name="carbon_fiber"> - <color rgba="0.3 0.3 0.3 1"/> - </material> - </visual> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/ring_small.dae"/> - </geometry> - </visual> - <collision> - <geometry> - <mesh filename="package://kinova_description/meshes/hand_2finger.dae"/> - </geometry> - </collision> - <inertial> - <mass value="0.99"/> - <origin xyz="0 0 -0.06"/> - <inertia ixx="0.0003453236187" ixy="0" ixz="0" iyy="0.0003453236187" iyz="0" izz="0.0005816"/> - </inertial> - </link> - <joint name="j2s6s200_joint_6" type="revolute"> - <parent link="j2s6s200_link_5"/> - <child link="j2s6s200_link_6"/> - <axis xyz="0 0 1"/> - <limit effort="20" lower="-6.28318530718" upper="6.28318530718" velocity="0.837758040957"/> - <origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0.10375 0"/> - <dynamics damping="0.0" friction="0.0"/> + <actuator name="j2s6s200_joint_4_actuator"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>160</mechanicalReduction> + </actuator> + </transmission> + <link name="j2s6s200_link_5"> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/wrist_spherical_2.dae"/> + </geometry> + <material name="carbon_fiber"> + <color rgba="0.3 0.3 0.3 1"/> + </material> + </visual> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/ring_small.dae"/> + </geometry> + </visual> + <collision> + <geometry> + <mesh filename="package://kinova_description/meshes/wrist_spherical_2.dae"/> + </geometry> + </collision> + <inertial> + <mass value="0.463"/> + <origin xyz="0 0.0497208855 -0.0028562765"/> + <inertia ixx="0.0004321316048" ixy="0" ixz="0" iyy="9.26e-05" iyz="0" izz="0.0004321316048"/> + </inertial> + </link> + <joint name="j2s6s200_joint_5" type="revolute"> + <parent link="j2s6s200_link_4"/> + <child link="j2s6s200_link_5"/> + <axis xyz="0 0 1"/> + <limit effort="20" lower="0.523598775598" upper="5.75958653158" velocity="0.837758040957"/> + <origin rpy="1.57079632679 0 3.14159265359" xyz="0 0 -0.10375"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <transmission name="j2s6s200_joint_5_trans"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="j2s6s200_joint_5"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> - <transmission name="j2s6s200_joint_6_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="j2s6s200_joint_6"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - </joint> - <actuator name="j2s6s200_joint_6_actuator"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - <mechanicalReduction>160</mechanicalReduction> - </actuator> - </transmission> - <link name="j2s6s200_end_effector"/> - <joint name="j2s6s200_joint_end_effector" type="fixed"> - <parent link="j2s6s200_link_6"/> - <child link="j2s6s200_end_effector"/> - <axis xyz="0 0 0"/> - <limit effort="2000" lower="0" upper="0" velocity="1"/> - <!-- <origin rpy="3.14159265359 0 1.57079632679" xyz="0 0 -0.1600"/> --> - <origin rpy="3.14159265359 1.57079632679 0" xyz="0 0 -0.1600"/> + <actuator name="j2s6s200_joint_5_actuator"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>160</mechanicalReduction> + </actuator> + </transmission> + <link name="j2s6s200_link_6"> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/hand_2finger.dae"/> + </geometry> + <material name="carbon_fiber"> + <color rgba="0.3 0.3 0.3 1"/> + </material> + </visual> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/ring_small.dae"/> + </geometry> + </visual> + <collision> + <geometry> + <mesh filename="package://kinova_description/meshes/hand_2finger.dae"/> + </geometry> + </collision> + <inertial> + <mass value="0.99"/> + <origin xyz="0 0 -0.06"/> + <inertia ixx="0.0003453236187" ixy="0" ixz="0" iyy="0.0003453236187" iyz="0" izz="0.0005816"/> + </inertial> + </link> + <joint name="j2s6s200_joint_6" type="revolute"><!-- revolute --> + <parent link="j2s6s200_link_5"/> + <child link="j2s6s200_link_6"/> + <axis xyz="0 0 1"/> + <limit effort="20" lower="-6.28318530718" upper="6.28318530718" velocity="0.837758040957"/> + <origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0.10375 0"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <transmission name="j2s6s200_joint_6_trans"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="j2s6s200_joint_6"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> - <link name="j2s6s200_link_finger_1"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> - </geometry> - <material name="carbon_fiber"> - <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> - </material> - </visual> - <collision> - <geometry> - <mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> - </geometry> - </collision> - <inertial> - <mass value="0.01"/> - <origin xyz="0.022 0 0"/> - <inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> - </inertial> - </link> - <joint name="j2s6s200_joint_finger_1" type="fixed"> - <parent link="j2s6s200_link_6"/> - <child link="j2s6s200_link_finger_1"/> - <axis xyz="0 0 1"/> - <origin rpy="-1.570796327 .649262481663582 1.57079632679490" xyz="-0.0025 0.03095 -0.11482"/> - <limit effort="2" lower="0" upper="1.51" velocity="1"/> + <actuator name="j2s6s200_joint_6_actuator"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>160</mechanicalReduction> + </actuator> + </transmission> + <link name="j2s6s200_end_effector"> + <inertial> + <mass value="0.001"/> + <inertia ixx="4.90e-07" ixy="0.0" ixz="0.0" iyy="4.90e-07" iyz="0.0" izz="4.90e-07"/> + <!-- for a sphere: 2/5 m * r**2 --> + </inertial> + </link> + <joint name="j2s6s200_joint_end_effector" type="fixed"> + <parent link="j2s6s200_link_6"/> + <child link="j2s6s200_end_effector"/> + <axis xyz="0 0 0"/> + <limit effort="2000" lower="0" upper="0" velocity="1"/> + <!-- <origin rpy="3.14159265359 0 1.57079632679" xyz="0 0 -0.1600"/> --> + <origin rpy="3.14159265359 1.57079632679 0" xyz="0 0 -0.1600"/> + </joint> + <link name="j2s6s200_link_finger_1"> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> + </geometry> + <material name="carbon_fiber"> + <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> + </material> + </visual> + <collision> + <geometry> + <mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> + </geometry> + </collision> + <inertial> + <mass value="0.01"/> + <origin xyz="0.022 0 0"/> + <inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> + </inertial> + </link> + <joint name="j2s6s200_joint_finger_1" type="fixed"> + <parent link="j2s6s200_link_6"/> + <child link="j2s6s200_link_finger_1"/> + <axis xyz="0 0 1"/> + <origin rpy="-1.570796327 .649262481663582 1.57079632679490" xyz="-0.0025 0.03095 -0.11482"/> + <limit effort="2" lower="0" upper="1.51" velocity="1"/> + </joint> + <transmission name="j2s6s200_joint_finger_1_trans"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="j2s6s200_joint_finger_1"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> - <transmission name="j2s6s200_joint_finger_1_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="j2s6s200_joint_finger_1"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - </joint> - <actuator name="j2s6s200_joint_finger_1_actuator"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - <mechanicalReduction>1</mechanicalReduction> - </actuator> - </transmission> - <link name="j2s6s200_link_finger_tip_1"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/finger_distal.dae"/> - </geometry> - <material name="carbon_fiber"> - <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> - </material> - </visual> - <collision> - <geometry> - <mesh filename="package://kinova_description/meshes/finger_distal.dae"/> - </geometry> - </collision> - <inertial> - <mass value="0.01"/> - <origin xyz="0.022 0 0"/> - <inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> - </inertial> - </link> - <joint name="j2s6s200_joint_finger_tip_1" type="fixed"> - <parent link="j2s6s200_link_finger_1"/> - <child link="j2s6s200_link_finger_tip_1"/> - <axis xyz="0 0 1"/> - <origin rpy="0 0 0" xyz="0.044 -0.003 0"/> - <limit effort="2" lower="0" upper="2" velocity="1"/> + <actuator name="j2s6s200_joint_finger_1_actuator"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <link name="j2s6s200_link_finger_tip_1"> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/finger_distal.dae"/> + </geometry> + <material name="carbon_fiber"> + <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> + </material> + </visual> + <collision> + <geometry> + <mesh filename="package://kinova_description/meshes/finger_distal.dae"/> + </geometry> + </collision> + <inertial> + <mass value="0.01"/> + <origin xyz="0.022 0 0"/> + <inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> + </inertial> + </link> + <joint name="j2s6s200_joint_finger_tip_1" type="fixed"> + <parent link="j2s6s200_link_finger_1"/> + <child link="j2s6s200_link_finger_tip_1"/> + <axis xyz="0 0 1"/> + <origin rpy="0 0 0" xyz="0.044 -0.003 0"/> + <limit effort="2" lower="0" upper="2" velocity="1"/> + </joint> + <transmission name="j2s6s200_joint_finger_tip_1_trans"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="j2s6s200_joint_finger_tip_1"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> - <transmission name="j2s6s200_joint_finger_tip_1_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="j2s6s200_joint_finger_tip_1"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - </joint> - <actuator name="j2s6s200_joint_finger_tip_1_actuator"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - <mechanicalReduction>1</mechanicalReduction> - </actuator> - </transmission> - <link name="j2s6s200_link_finger_2"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> - </geometry> - <material name="carbon_fiber"> - <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> - </material> - </visual> - <collision> - <geometry> - <mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> - </geometry> - </collision> - <inertial> - <mass value="0.01"/> - <origin xyz="0.022 0 0"/> - <inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> - </inertial> - </link> - <joint name="j2s6s200_joint_finger_2" type="fixed"> - <parent link="j2s6s200_link_6"/> - <child link="j2s6s200_link_finger_2"/> - <axis xyz="0 0 1"/> - <origin rpy="-1.570796327 .649262481663582 -1.57079632679490" xyz="-0.0025 -0.03095 -0.11482"/> - <limit effort="2" lower="0" upper="1.51" velocity="1"/> + <actuator name="j2s6s200_joint_finger_tip_1_actuator"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <link name="j2s6s200_link_finger_2"> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> + </geometry> + <material name="carbon_fiber"> + <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> + </material> + </visual> + <collision> + <geometry> + <mesh filename="package://kinova_description/meshes/finger_proximal.dae"/> + </geometry> + </collision> + <inertial> + <mass value="0.01"/> + <origin xyz="0.022 0 0"/> + <inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> + </inertial> + </link> + <joint name="j2s6s200_joint_finger_2" type="fixed"> + <parent link="j2s6s200_link_6"/> + <child link="j2s6s200_link_finger_2"/> + <axis xyz="0 0 1"/> + <origin rpy="-1.570796327 .649262481663582 -1.57079632679490" xyz="-0.0025 -0.03095 -0.11482"/> + <limit effort="2" lower="0" upper="1.51" velocity="1"/> + </joint> + <transmission name="j2s6s200_joint_finger_2_trans"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="j2s6s200_joint_finger_2"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> - <transmission name="j2s6s200_joint_finger_2_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="j2s6s200_joint_finger_2"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - </joint> - <actuator name="j2s6s200_joint_finger_2_actuator"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - <mechanicalReduction>1</mechanicalReduction> - </actuator> - </transmission> - <link name="j2s6s200_link_finger_tip_2"> - <visual> - <geometry> - <mesh filename="package://kinova_description/meshes/finger_distal.dae"/> - </geometry> - <material name="carbon_fiber"> - <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> - </material> - </visual> - <collision> - <geometry> - <mesh filename="package://kinova_description/meshes/finger_distal.dae"/> - </geometry> - </collision> - <inertial> - <mass value="0.01"/> - <origin xyz="0.022 0 0"/> - <inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> - </inertial> - </link> - <joint name="j2s6s200_joint_finger_tip_2" type="fixed"> - <parent link="j2s6s200_link_finger_2"/> - <child link="j2s6s200_link_finger_tip_2"/> - <axis xyz="0 0 1"/> - <origin rpy="0 0 0" xyz="0.044 -0.003 0"/> - <limit effort="2" lower="0" upper="2" velocity="1"/> + <actuator name="j2s6s200_joint_finger_2_actuator"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <link name="j2s6s200_link_finger_tip_2"> + <visual> + <geometry> + <mesh filename="package://kinova_description/meshes/finger_distal.dae"/> + </geometry> + <material name="carbon_fiber"> + <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> + </material> + </visual> + <collision> + <geometry> + <mesh filename="package://kinova_description/meshes/finger_distal.dae"/> + </geometry> + </collision> + <inertial> + <mass value="0.01"/> + <origin xyz="0.022 0 0"/> + <inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> + </inertial> + </link> + <joint name="j2s6s200_joint_finger_tip_2" type="fixed"> + <parent link="j2s6s200_link_finger_2"/> + <child link="j2s6s200_link_finger_tip_2"/> + <axis xyz="0 0 1"/> + <origin rpy="0 0 0" xyz="0.044 -0.003 0"/> + <limit effort="2" lower="0" upper="2" velocity="1"/> + </joint> + <transmission name="j2s6s200_joint_finger_tip_2_trans"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="j2s6s200_joint_finger_tip_2"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> - <transmission name="j2s6s200_joint_finger_tip_2_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="j2s6s200_joint_finger_tip_2"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - </joint> - <actuator name="j2s6s200_joint_finger_tip_2_actuator"> - <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> - <mechanicalReduction>1</mechanicalReduction> - </actuator> - </transmission> - + <actuator name="j2s6s200_joint_finger_tip_2_actuator"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> </robot> diff --git a/robots/anymal_b_simple_description/robots/anymal.urdf b/robots/anymal_b_simple_description/robots/anymal.urdf index b5dd522db1d287db5d68e2101e876b5ac149cd8a..42124ba06d68fe9fb720cf929184b5df2a8c7a2e 100644 --- a/robots/anymal_b_simple_description/robots/anymal.urdf +++ b/robots/anymal_b_simple_description/robots/anymal.urdf @@ -1,10 +1,10 @@ <?xml version="1.0" ?> <!-- =================================================================================== --> -<!-- | This document was autogenerated by xacro from anymal.urdf.xacro | --> -<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> +<!-- | This URDF was edited to fix inertias. | --> <!-- =================================================================================== --> <!-- This file contains the description of the ANYmal B robot. --> -<robot name="anymal" xmlns:xacro="http://www.ros.org/wiki/xacro"> +<robot name="anymal" + xmlns:xacro="http://www.ros.org/wiki/xacro"> <material name="black"> <color rgba="0.0 0.0 0.0 1.0"/> </material> @@ -100,21 +100,26 @@ <box size="0.531 0.02 0.07"/> </geometry> </collision> + <inertial> + <origin rpy="0 0 0" xyz="-0.001960558279 -0.001413217745 0.050207125344"/> + <mass value="16.793507758"/> + <inertia ixx="0.217391101503" ixy="-0.00132873239126" ixz="-0.00228200226173" iyy="0.639432546734" iyz="-0.00138078263145" izz="0.62414077654"/> + </inertial> </link> <!-- Fixed joint to add dummy inertia link --> - <joint name="base_to_base_inertia" type="fixed"> + <!-- <joint name="base_to_base_inertia" type="fixed"> <parent link="base"/> <child link="base_inertia"/> <origin rpy="0 0 0" xyz="0 0 0"/> - </joint> + </joint> --> <!-- Dummy inertia link, because KDL cannot have inertia on the base link --> - <link name="base_inertia"> + <!-- <link name="base_inertia"> <inertial> <origin rpy="0 0 0" xyz="-0.001960558279 -0.001413217745 0.050207125344"/> <mass value="16.793507758"/> <inertia ixx="0.217391101503" ixy="-0.00132873239126" ixz="-0.00228200226173" iyy="0.639432546734" iyz="-0.00138078263145" izz="0.62414077654"/> </inertial> - </link> + </link> --> <!-- Xacro:Properties --> <!-- [kg * m^2] --> <!-- [A] --> @@ -278,6 +283,18 @@ <sphere radius="0.031"/> </geometry> </collision> + <inertial> + <mass value="0.001"/> + <inertia ixx="4.90e-07" ixy="0.0" ixz="0.0" iyy="4.90e-07" iyz="0.0" izz="4.90e-07"/> + <!-- for a sphere: 2/5 m * r**2 --> + </inertial> + <!-- Bullet specific parameters --> + <contact> + <lateral_friction value="1.0"/> + <stiffness value="300000"/> + <damping value="15000"/> + <!--<restitution value="0.5"/>--> + </contact> </link> <!-- Gazebo customization --> <gazebo reference="LF_FOOT"> @@ -449,6 +466,18 @@ <sphere radius="0.031"/> </geometry> </collision> + <inertial> + <mass value="0.001"/> + <inertia ixx="4.90e-07" ixy="0.0" ixz="0.0" iyy="4.90e-07" iyz="0.0" izz="4.90e-07"/> + <!-- for a sphere: 2/5 m * r**2 --> + </inertial> + <!-- Bullet specific parameters --> + <contact> + <lateral_friction value="1.0"/> + <stiffness value="300000"/> + <damping value="15000"/> + <!--<restitution value="0.5"/>--> + </contact> </link> <!-- Gazebo customization --> <gazebo reference="RF_FOOT"> @@ -620,6 +649,18 @@ <sphere radius="0.031"/> </geometry> </collision> + <inertial> + <mass value="0.001"/> + <inertia ixx="4.90e-07" ixy="0.0" ixz="0.0" iyy="4.90e-07" iyz="0.0" izz="4.90e-07"/> + <!-- for a sphere: 2/5 m * r**2 --> + </inertial> + <!-- Bullet specific parameters --> + <contact> + <lateral_friction value="1.0"/> + <stiffness value="300000"/> + <damping value="15000"/> + <!--<restitution value="0.5"/>--> + </contact> </link> <!-- Gazebo customization --> <gazebo reference="LH_FOOT"> @@ -791,6 +832,18 @@ <sphere radius="0.031"/> </geometry> </collision> + <inertial> + <mass value="0.001"/> + <inertia ixx="4.90e-07" ixy="0.0" ixz="0.0" iyy="4.90e-07" iyz="0.0" izz="4.90e-07"/> + <!-- for a sphere: 2/5 m * r**2 --> + </inertial> + <!-- Bullet specific parameters --> + <contact> + <lateral_friction value="1.0"/> + <stiffness value="300000"/> + <damping value="15000"/> + <!--<restitution value="0.5"/>--> + </contact> </link> <!-- Gazebo customization --> <gazebo reference="RH_FOOT"> diff --git a/robots/hyq_description/robots/hyq_no_sensors.urdf b/robots/hyq_description/robots/hyq_no_sensors.urdf index 7de0fa9657ea436fdb0b6bd060ee8c121f246322..9b2b221edf059b63282c26b13b1e13b5b2f378a4 100644 --- a/robots/hyq_description/robots/hyq_no_sensors.urdf +++ b/robots/hyq_description/robots/hyq_no_sensors.urdf @@ -73,6 +73,10 @@ is the world frame). For more, see http://ros.org/wiki/xacro --> <!-- Links --> <!-- Footprint link --> <link name="base_link"> + <inertial> + <mass value="1e-6"/> + <inertia ixx="1e-6" ixy="1e-6" ixz="1e-6" iyy="1e-6" iyz="1e-6" izz="1e-6"/> + </inertial> <visual> <geometry> <cylinder length="0.01" radius="0.01"/> @@ -203,6 +207,15 @@ is the world frame). For more, see http://ros.org/wiki/xacro --> </link> <!-- Foot link --> <link name="lf_foot"> + <contact> + <lateral_friction value="1"/> + <stiffness value="30000"/> + <damping value="1000"/> + </contact> + <inertial> + <mass value="1e-6"/> + <inertia ixx="1e-6" ixy="1e-6" ixz="1e-6" iyy="1e-6" iyz="1e-6" izz="1e-6"/> + </inertial> <collision> <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> @@ -409,6 +422,15 @@ is the world frame). For more, see http://ros.org/wiki/xacro --> </link> <!-- Foot link --> <link name="rf_foot"> + <contact> + <lateral_friction value="1"/> + <stiffness value="30000"/> + <damping value="1000"/> + </contact> + <inertial> + <mass value="1e-6"/> + <inertia ixx="1e-6" ixy="1e-6" ixz="1e-6" iyy="1e-6" iyz="1e-6" izz="1e-6"/> + </inertial> <collision> <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> @@ -615,6 +637,15 @@ is the world frame). For more, see http://ros.org/wiki/xacro --> </link> <!-- Foot link --> <link name="lh_foot"> + <contact> + <lateral_friction value="1"/> + <stiffness value="30000"/> + <damping value="1000"/> + </contact> + <inertial> + <mass value="1e-6"/> + <inertia ixx="1e-6" ixy="1e-6" ixz="1e-6" iyy="1e-6" iyz="1e-6" izz="1e-6"/> + </inertial> <collision> <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> @@ -821,6 +852,15 @@ is the world frame). For more, see http://ros.org/wiki/xacro --> </link> <!-- Foot link --> <link name="rh_foot"> + <contact> + <lateral_friction value="1"/> + <stiffness value="30000"/> + <damping value="1000"/> + </contact> + <inertial> + <mass value="1e-6"/> + <inertia ixx="1e-6" ixy="1e-6" ixz="1e-6" iyy="1e-6" iyz="1e-6" izz="1e-6"/> + </inertial> <collision> <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> diff --git a/robots/romeo_description/meshes/PLACEHOLDER b/robots/romeo_description/meshes/PLACEHOLDER deleted file mode 100644 index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000 diff --git a/robots/romeo_description/meshes/convert.sh b/robots/romeo_description/meshes/convert.sh deleted file mode 100755 index 6154aad15947db17661af26f6d2a0ea406b0fdaf..0000000000000000000000000000000000000000 --- a/robots/romeo_description/meshes/convert.sh +++ /dev/null @@ -1,4 +0,0 @@ -#!/bin/sh -for i in `find . -name '*.wrl'`; do - meshlabserver -i $i -o `pwd`/$(echo `basename $i` | sed 's|.wrl$|.dae|') -done