Commit 37ffd231 authored by Joseph Mirabel's avatar Joseph Mirabel Committed by olivier stasse
Browse files

[steel] Make some joints fixed.

parent fd72b1b1
......@@ -552,7 +552,7 @@
<kinematic>0</kinematic>
<gravity>1</gravity>
</link>
<joint name="suspension_right_joint" type="prismatic">
<joint name="suspension_right_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="100.0" lower="-0.005" upper="0.005" velocity="1.0"/>
......@@ -562,7 +562,7 @@
<dynamics damping="100"/>
<safety_controller k_position="0" k_velocity="10" soft_lower_limit="-0.005" soft_upper_limit="0.005"/>
</joint>
<joint name="wheel_right_joint" type="continuous">
<joint name="wheel_right_joint" type="fixed">
<parent link="suspension_right_link"/>
<child link="wheel_right_link"/>
<origin rpy="-1.57079632679 0 0" xyz="0 -0.2022 0"/>
......@@ -620,7 +620,7 @@
<kinematic>0</kinematic>
<gravity>1</gravity>
</link>
<joint name="suspension_left_joint" type="prismatic">
<joint name="suspension_left_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="100.0" lower="-0.005" upper="0.005" velocity="1.0"/>
......@@ -630,7 +630,7 @@
<dynamics damping="100"/>
<safety_controller k_position="0" k_velocity="10" soft_lower_limit="-0.005" soft_upper_limit="0.005"/>
</joint>
<joint name="wheel_left_joint" type="continuous">
<joint name="wheel_left_joint" type="fixed">
<parent link="suspension_left_link"/>
<child link="wheel_left_link"/>
<origin rpy="-1.57079632679 0 0" xyz="0 0.2022 0"/>
......@@ -699,14 +699,14 @@
</geometry>
</collision>
</link>
<joint name="caster_front_right_1_joint" type="continuous">
<joint name="caster_front_right_1_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_front_right_1_link"/>
<origin rpy="0 0 0" xyz="0.1695 -0.102 -0.0335"/>
<axis xyz="0 0 1"/>
<dynamics damping="0.005" friction="0.0"/>
</joint>
<joint name="caster_front_right_2_joint" type="continuous">
<joint name="caster_front_right_2_joint" type="fixed">
<parent link="caster_front_right_1_link"/>
<child link="caster_front_right_2_link"/>
<origin rpy="-1.57079632679 0 0" xyz="-0.016 0.0000 -0.040"/>
......@@ -775,14 +775,14 @@
</geometry>
</collision>
</link>
<joint name="caster_front_left_1_joint" type="continuous">
<joint name="caster_front_left_1_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_front_left_1_link"/>
<origin rpy="0 0 0" xyz="0.1695 0.102 -0.0335"/>
<axis xyz="0 0 1"/>
<dynamics damping="0.005" friction="0.0"/>
</joint>
<joint name="caster_front_left_2_joint" type="continuous">
<joint name="caster_front_left_2_joint" type="fixed">
<parent link="caster_front_left_1_link"/>
<child link="caster_front_left_2_link"/>
<origin rpy="-1.57079632679 0 0" xyz="-0.016 0.0000 -0.040"/>
......@@ -851,14 +851,14 @@
</geometry>
</collision>
</link>
<joint name="caster_back_right_1_joint" type="continuous">
<joint name="caster_back_right_1_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_back_right_1_link"/>
<origin rpy="0 0 0" xyz="-0.1735 -0.102 -0.0335"/>
<axis xyz="0 0 1"/>
<dynamics damping="0.005" friction="0.0"/>
</joint>
<joint name="caster_back_right_2_joint" type="continuous">
<joint name="caster_back_right_2_joint" type="fixed">
<parent link="caster_back_right_1_link"/>
<child link="caster_back_right_2_link"/>
<origin rpy="-1.57079632679 0 0" xyz="-0.016 0.0000 -0.040"/>
......@@ -927,14 +927,14 @@
</geometry>
</collision>
</link>
<joint name="caster_back_left_1_joint" type="continuous">
<joint name="caster_back_left_1_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_back_left_1_link"/>
<origin rpy="0 0 0" xyz="-0.1735 0.102 -0.0335"/>
<axis xyz="0 0 1"/>
<dynamics damping="0.005" friction="0.0"/>
</joint>
<joint name="caster_back_left_2_joint" type="continuous">
<joint name="caster_back_left_2_joint" type="fixed">
<parent link="caster_back_left_1_link"/>
<child link="caster_back_left_2_link"/>
<origin rpy="-1.57079632679 0 0" xyz="-0.016 0.0000 -0.040"/>
......@@ -1775,7 +1775,7 @@
<gazebo reference="gripper_right_finger_link">
<material>Gazebo/Black</material>
</gazebo>
<joint name="gripper_right_finger_joint" type="prismatic">
<joint name="gripper_right_finger_joint" type="fixed">
<parent link="gripper_link"/>
<child link="gripper_right_finger_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.034 0.00000 0.00000"/>
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment