2 import pinocchio
as pin
5 @unittest.skipUnless(pin.WITH_URDFDOM,
"Needs URDFDOM")
9 self.
current_file = os.path.dirname(str(os.path.abspath(__file__)))
15 pin.buildModelFromUrdf(self.
model_path, pin.JointModelFreeFlyer())
19 pin.buildModelFromUrdf(self.
model_path, pin.JointModelFreeFlyer(), model)
20 pin.buildModelFromUrdf(self.
model_path, pin.JointModelFreeFlyer())
24 file_content = model.read()
26 model_ref = pin.buildModelFromUrdf(self.
model_path, pin.JointModelFreeFlyer())
27 model = pin.buildModelFromXML(file_content,pin.JointModelFreeFlyer())
29 self.assertEqual(model,model_ref)
31 model_self = pin.Model()
32 pin.buildModelFromXML(file_content,pin.JointModelFreeFlyer(),model_self)
33 self.assertEqual(model_self,model_ref)
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"))
41 model = pin.buildModelFromUrdf(model_path)
42 filename =
"model.pickle" 43 with
open(filename,
'wb')
as f:
46 with
open(filename,
'rb')
as f:
47 model_copy = pickle.load(f)
49 self.assertTrue(model == model_copy)
51 if __name__ ==
'__main__':