bindings_urdf.py
Go to the documentation of this file.
1 import unittest
2 import pinocchio as pin
3 import os
4 
5 @unittest.skipUnless(pin.WITH_URDFDOM,"Needs URDFDOM")
6 class TestGeometryObjectUrdfBindings(unittest.TestCase):
7 
8  def setUp(self):
9  self.current_file = os.path.dirname(str(os.path.abspath(__file__)))
10  self.model_dir = os.path.abspath(os.path.join(self.current_file, "../../models/example-robot-data/robots"))
11  self.model_path = os.path.abspath(os.path.join(self.model_dir, "romeo_description/urdf/romeo.urdf"))
12 
13  def test_load(self):
14  pin.buildModelFromUrdf(self.model_path)
15  pin.buildModelFromUrdf(self.model_path, pin.JointModelFreeFlyer())
16 
17  def test_self_load(self):
18  model = pin.Model()
19  pin.buildModelFromUrdf(self.model_path, pin.JointModelFreeFlyer(), model)
20  pin.buildModelFromUrdf(self.model_path, pin.JointModelFreeFlyer())
21 
22  def test_xml(self):
23  with open(self.model_path) as model:
24  file_content = model.read()
25 
26  model_ref = pin.buildModelFromUrdf(self.model_path, pin.JointModelFreeFlyer())
27  model = pin.buildModelFromXML(file_content,pin.JointModelFreeFlyer())
28 
29  self.assertEqual(model,model_ref)
30 
31  model_self = pin.Model()
32  pin.buildModelFromXML(file_content,pin.JointModelFreeFlyer(),model_self)
33  self.assertEqual(model_self,model_ref)
34 
35  def test_pickle(self):
36  import pickle
37 
38  model_dir = os.path.abspath(os.path.join(self.current_file, "../../models/example-robot-data/robots"))
39  model_path = os.path.abspath(os.path.join(model_dir, "ur_description/urdf/ur5_robot.urdf"))
40 
41  model = pin.buildModelFromUrdf(model_path)
42  filename = "model.pickle"
43  with open(filename, 'wb') as f:
44  pickle.dump(model,f)
45 
46  with open(filename, 'rb') as f:
47  model_copy = pickle.load(f)
48 
49  self.assertTrue(model == model_copy)
50 
51 if __name__ == '__main__':
52  unittest.main()


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:28