Skip to content

Commit 7ca2810

Browse files
authored
Fix UTF8 reading. (#83)
Do this by opening files in binary mode, which will allow the XML parser to convert to UTF-8 if it is specified. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 9c8ab87 commit 7ca2810

File tree

3 files changed

+17
-2
lines changed

3 files changed

+17
-2
lines changed

src/urdf_parser_py/display_urdf.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66

77
def main():
88
parser = argparse.ArgumentParser(usage='Load an URDF file')
9-
parser.add_argument('file', type=argparse.FileType('r'),
9+
parser.add_argument('file', type=argparse.FileType('rb'),
1010
help='File to load. Use - for stdin')
1111
parser.add_argument('-o', '--output', type=argparse.FileType('w'),
1212
default=None, help='Dump file to XML')

src/urdf_parser_py/xml_reflection/core.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -613,7 +613,7 @@ def from_xml_string(cls, xml_string):
613613

614614
@classmethod
615615
def from_xml_file(cls, file_path):
616-
xml_string = open(file_path, 'r').read()
616+
xml_string = open(file_path, 'rb').read()
617617
return cls.from_xml_string(xml_string)
618618

619619
# Confusing distinction between loading code in object and reflection

test/test_urdf.py

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -289,6 +289,21 @@ def test_robot_link_defaults_xyz_set(self):
289289
self.assertEqual(origin.xyz, [1, 2, 3])
290290
self.assertEqual(origin.rpy, [0, 0, 0])
291291

292+
def test_xml_with_UTF8_encoding(self):
293+
xml = b'''<?xml version="1.0" encoding="UTF-8"?>
294+
<robot name="test">
295+
<link name="test_link">
296+
<inertial>
297+
<mass value="10.0"/>
298+
<origin xyz="1 2 3"/>
299+
</inertial>
300+
</link>
301+
</robot>'''
302+
robot = self.parse(xml)
303+
origin = robot.links[0].inertial.origin
304+
self.assertEqual(origin.xyz, [1, 2, 3])
305+
self.assertEqual(origin.rpy, [0, 0, 0])
306+
292307

293308
class LinkMultiVisualsAndCollisionsTest(unittest.TestCase):
294309

0 commit comments

Comments
 (0)