Skip to content

Commit

Permalink
Added in test for pelican_urdf
Browse files Browse the repository at this point in the history
  • Loading branch information
eacousineau committed Jul 11, 2013
1 parent 09a748c commit 763e0fc
Show file tree
Hide file tree
Showing 4 changed files with 143 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -1,13 +1,15 @@
#!/usr/bin/env python

import roslib; roslib.load_manifest('urdf_parser_py')

import sys
import argparse

from urdf_parser_py.urdf import URDF

parser = argparse.ArgumentParser(usage='Load an URDF file')
parser.add_argument('file', type=argparse.FileType('r'), nargs='?', default=None, help='File to load. Use - for stdin')
parser.add_argument('-o', '--output', type=argparse.FileType('w'), default=None, help='Dump file to XML')
args = parser.parse_args()

if args.file is None:
Expand All @@ -16,3 +18,6 @@ else:
robot = URDF.from_xml_string(args.file.read())

print robot

if args.output is not None:
args.output.write(robot.to_xml_string())
130 changes: 130 additions & 0 deletions urdf_parser_py/test/pelican_gen_mer.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,130 @@
--- /tmp/pelican.urdf 2013-04-11 09:24:30.325804322 -0500
+++ /tmp/tmp.urdf 2013-04-11 09:26:50.185809508 -0500
@@ -1,111 +1,78 @@
+<?xml version="1.0"?>
<robot name="Asctec Pelican">
-
-################################################################################
-# LINKS #
-################################################################################
-
- ##### base_link ##############################################################
-
<link name="base_link">
<visual>
- <origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 3.1415"/>
+ <origin rpy="1.57 0.0 3.1415" xyz="0.0 0.0 0.0"/>
<geometry>
- <mesh filename="package://pelican_urdf/data/pelican.stl"
- scale="0.001 0.001 0.001"/>
+ <mesh filename="package://pelican_urdf/data/pelican.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="blue">
<color rgba="0.4 0.4 0.5 1.0"/>
</material>
</visual>
</link>
-
- ##### base_footprint #########################################################
-
<link name="base_footprint"/>
-
- ##### legs ###################################################################
-
<link name="leg_1">
<visual>
+ <origin rpy="0.0 0.0 0.0" xyz="0.089 0.0 -0.057"/>
<geometry>
- <box size="0.044 0.007 0.114"/>
+ <box size="0.044 0.007 0.114"/>
</geometry>
- <origin xyz="0.089 0.00 -0.057" rpy="0.0 0.0 0.0"/>
<material name="g">
<color rgba="0.2 0.25 0.25 1.0"/>
</material>
</visual>
</link>
-
<link name="leg_2">
<visual>
+ <origin rpy="0.0 0.0 0.0" xyz="-0.089 0.0 -0.057"/>
<geometry>
- <box size="0.044 0.007 0.114"/>
+ <box size="0.044 0.007 0.114"/>
</geometry>
- <origin xyz="-0.089 0.00 -0.057" rpy="0.0 0.0 0.0"/>
<material name="g"/>
</visual>
</link>
-
<link name="leg_3">
<visual>
+ <origin rpy="0.0 0.0 1.5708" xyz="0.0 0.089 -0.057"/>
<geometry>
- <box size="0.044 0.007 0.114"/>
+ <box size="0.044 0.007 0.114"/>
</geometry>
- <origin xyz="0.00 0.089 -0.057" rpy="0.0 0.0 1.5708"/>
<material name="g"/>
</visual>
</link>
-
<link name="leg_4">
<visual>
+ <origin rpy="0.0 0.0 1.5708" xyz="0.0 -0.089 -0.057"/>
<geometry>
- <box size="0.044 0.007 0.114"/>
+ <box size="0.044 0.007 0.114"/>
</geometry>
- <origin xyz="0.00 -0.089 -0.057" rpy="0.0 0.0 1.5708"/>
<material name="g"/>
</visual>
</link>
-
-################################################################################
-# JOINTS #
-################################################################################
-
- ##### base_footprint #########################################################
-
<joint name="base_link_to_base_footprint" type="fixed">
<parent link="base_link"/>
<child link="base_footprint"/>
- <origin xyz="0.00 0.00 -0.195" rpy="0.0 0.0 0.0"/>
+ <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 -0.195"/>
</joint>
-
- ##### legs ###################################################################
-
<joint name="base_link_to_leg_1" type="fixed">
<parent link="base_link"/>
<child link="leg_1"/>
- <origin xyz="0.00 0.00 -0.083" rpy="0.0 0.0 0.0"/>
+ <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 -0.083"/>
</joint>
-
<joint name="base_link_to_leg_2" type="fixed">
<parent link="base_link"/>
<child link="leg_2"/>
- <origin xyz="0.00 0.00 -0.083" rpy="0.0 0.0 0.0"/>
+ <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 -0.083"/>
</joint>
-
<joint name="base_link_to_leg_3" type="fixed">
<parent link="base_link"/>
<child link="leg_3"/>
- <origin xyz="0.00 0.00 -0.083" rpy="0.0 0.0 0.0"/>
+ <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 -0.083"/>
</joint>
-
<joint name="base_link_to_leg_4" type="fixed">
<parent link="base_link"/>
<child link="leg_4"/>
- <origin xyz="0.00 0.00 -0.083" rpy="0.0 0.0 0.0"/>
+ <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 -0.083"/>
</joint>
-
</robot>
-
-
-
3 changes: 3 additions & 0 deletions urdf_parser_py/test/pelican_test.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
<launch>
<param name="robot_description" command="cat $(find pelican_urdf)/data/pelican.xml" />
</launch>
5 changes: 5 additions & 0 deletions urdf_parser_py/test/pelican_test.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
#!/bin/bash
roslaunch ./pelican_test.launch
rosrun urdf_parser_py display_urdf -o /tmp/pelican_gen.urdf
python -c 'import rospy; open("/tmp/pelicant.urdf").write(rospy.get_param("/robot_description"))'
diff -u /tmp/pelican.urdf /tmp/pelican_gen.urdf

0 comments on commit 763e0fc

Please sign in to comment.