Skip to content

Commit

Permalink
rotate the ABB base by 90 degrees, fix a bug in ATI sensor urdf
Browse files Browse the repository at this point in the history
  • Loading branch information
hongkai-dai committed Mar 3, 2015
1 parent b1fd26c commit 5deae73
Show file tree
Hide file tree
Showing 5 changed files with 17 additions and 17 deletions.
2 changes: 1 addition & 1 deletion examples/IRB140/runPlanning.m
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
options.base_offset = [0.0, 0, 0.0]';
end
if ~isfield(options,'base_rpy')
options.base_rpy = [-pi/2, 0.0, 0]';
options.base_rpy = [0, 0.0, 0]';
end

r=RigidBodyManipulator();
Expand Down
4 changes: 2 additions & 2 deletions examples/IRB140/urdf/ATI_sensor.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
rpy="1.5707963267949 0 0" />
<geometry>
<mesh
filename="package://IRB140/urdf/meshes/ATI_sensor.STL" />
filename="package://IRB140/urdf/meshes/ATI_sensor.stl" />
</geometry>
<material
name="">
Expand All @@ -36,7 +36,7 @@
rpy="1.5707963267949 0 0" />
<geometry>
<mesh
filename="package://IRB140/urdf/meshes/ATI_sensor.STL" />
filename="package://IRB140/urdf/meshes/ATI_sensor.stl" />
</geometry>
</collision>
</link>
Expand Down
8 changes: 4 additions & 4 deletions examples/IRB140/urdf/irb_140.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<inertial>
<origin
xyz="-0.0820393251688425 -0.0599247343482246 0.000402028640224033"
rpy="0 0 0" />
rpy="-1.57079 0 0" />
<mass
value="12.409016159487" />
<inertia
Expand All @@ -20,7 +20,7 @@
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
rpy="-1.57079 0 0" />
<geometry>
<mesh
filename="package://IRB140/urdf/meshes/base_link.stl" />
Expand All @@ -34,7 +34,7 @@
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
rpy="-1.57079 0 0" />
<geometry>
<mesh
filename="package://IRB140/urdf/meshes/base_link.stl" />
Expand Down Expand Up @@ -292,7 +292,7 @@
<child link="link_1"/>
<limit effort="300" lower="-3.14159265359" upper="3.14159265359" velocity="4.36"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="0 -0.1095 0"/>
<origin rpy="-1.57079 0 0" xyz="0 0 0.1095"/>
</joint>
<joint name="joint2" type="revolute">
<parent link="link_1"/>
Expand Down
8 changes: 4 additions & 4 deletions examples/IRB140/urdf/irb_140_robotiq.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@
<robot name="IRB140" xmlns:xacro="http://ros.org/wiki/xacro">
<link name="base_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.0820393251688425 -0.0599247343482246 0.000402028640224033"/>
<origin rpy="-1.57079 0 0" xyz="-0.0820393251688425 -0.0599247343482246 0.000402028640224033"/>
<mass value="12.409016159487"/>
<inertia ixx="0.104502176006253" ixy="0.00734284655670482" ixz="1.00520827530156E-05" iyy="0.246486764065977" iyz="0.000843006810157312" izz="0.16727784258504"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="-1.57079 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://IRB140/urdf/meshes/base_link.stl"/>
</geometry>
Expand All @@ -20,7 +20,7 @@
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="-1.57079 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://IRB140/urdf/meshes/base_link.stl"/>
</geometry>
Expand Down Expand Up @@ -169,7 +169,7 @@
<child link="link_1"/>
<limit effort="300" lower="-3.14159265359" upper="3.14159265359" velocity="4.36"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="0 -0.1095 0"/>
<origin rpy="-1.57079 0 0" xyz="0 0 0.1095"/>
</joint>
<joint name="joint2" type="revolute">
<parent link="link_1"/>
Expand Down
12 changes: 6 additions & 6 deletions examples/IRB140/urdf/irb_140_robotiq_ati.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -1052,12 +1052,12 @@
</gazebo>
<link name="base_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.0820393251688425 -0.0599247343482246 0.000402028640224033"/>
<origin rpy="-1.57079 0 0" xyz="-0.0820393251688425 -0.0599247343482246 0.000402028640224033"/>
<mass value="12.409016159487"/>
<inertia ixx="0.104502176006253" ixy="0.00734284655670482" ixz="1.00520827530156E-05" iyy="0.246486764065977" iyz="0.000843006810157312" izz="0.16727784258504"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="-1.57079 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://IRB140/urdf/meshes/base_link.stl"/>
</geometry>
Expand All @@ -1066,7 +1066,7 @@
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="-1.57079 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://IRB140/urdf/meshes/base_link.stl"/>
</geometry>
Expand Down Expand Up @@ -1215,7 +1215,7 @@
<child link="link_1"/>
<limit effort="300" lower="-3.14159265359" upper="3.14159265359" velocity="4.36"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="0 -0.1095 0"/>
<origin rpy="-1.57079 0 0" xyz="0 0 0.1095"/>
</joint>
<joint name="joint2" type="revolute">
<parent link="link_1"/>
Expand Down Expand Up @@ -1291,7 +1291,7 @@
<visual>
<origin rpy="1.5707963267949 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://IRB140/urdf/meshes/ATI_sensor.STL"/>
<mesh filename="package://IRB140/urdf/meshes/ATI_sensor.stl"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
Expand All @@ -1300,7 +1300,7 @@
<collision>
<origin rpy="1.5707963267949 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://IRB140/urdf/meshes/ATI_sensor.STL"/>
<mesh filename="package://IRB140/urdf/meshes/ATI_sensor.stl"/>
</geometry>
</collision>
</link>
Expand Down

0 comments on commit 5deae73

Please sign in to comment.