Skip to content

Commit

Permalink
Fix UTF8 reading. (#83)
Browse files Browse the repository at this point in the history
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]>
  • Loading branch information
clalancette authored Dec 1, 2023
1 parent 9c8ab87 commit 7ca2810
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 2 deletions.
2 changes: 1 addition & 1 deletion src/urdf_parser_py/display_urdf.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

def main():
parser = argparse.ArgumentParser(usage='Load an URDF file')
parser.add_argument('file', type=argparse.FileType('r'),
parser.add_argument('file', type=argparse.FileType('rb'),
help='File to load. Use - for stdin')
parser.add_argument('-o', '--output', type=argparse.FileType('w'),
default=None, help='Dump file to XML')
Expand Down
2 changes: 1 addition & 1 deletion src/urdf_parser_py/xml_reflection/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -613,7 +613,7 @@ def from_xml_string(cls, xml_string):

@classmethod
def from_xml_file(cls, file_path):
xml_string = open(file_path, 'r').read()
xml_string = open(file_path, 'rb').read()
return cls.from_xml_string(xml_string)

# Confusing distinction between loading code in object and reflection
Expand Down
15 changes: 15 additions & 0 deletions test/test_urdf.py
Original file line number Diff line number Diff line change
Expand Up @@ -289,6 +289,21 @@ def test_robot_link_defaults_xyz_set(self):
self.assertEqual(origin.xyz, [1, 2, 3])
self.assertEqual(origin.rpy, [0, 0, 0])

def test_xml_with_UTF8_encoding(self):
xml = b'''<?xml version="1.0" encoding="UTF-8"?>
<robot name="test">
<link name="test_link">
<inertial>
<mass value="10.0"/>
<origin xyz="1 2 3"/>
</inertial>
</link>
</robot>'''
robot = self.parse(xml)
origin = robot.links[0].inertial.origin
self.assertEqual(origin.xyz, [1, 2, 3])
self.assertEqual(origin.rpy, [0, 0, 0])


class LinkMultiVisualsAndCollisionsTest(unittest.TestCase):

Expand Down

0 comments on commit 7ca2810

Please sign in to comment.