1 import pinocchio
as pin
10 pinocchio_model_dir = join(dirname(dirname(str(abspath(__file__)))),
"models")
11 model_path = pinocchio_model_dir +
'/example-robot-data/robots' 12 mesh_dir = pinocchio_model_dir
14 urdf_filename = model_path +
'/ur_description/urdf/ur5_robot.urdf' 15 model, collision_model, visual_model = pin.buildModelsFromUrdf(urdf_filename, mesh_dir)
18 print(
'standard model: dim=' + str(len(model.joints)))
19 for jn
in model.joints:
24 jointsToLock = [
'wrist_1_joint',
'wrist_2_joint',
'wrist_3_joint']
28 for jn
in jointsToLock:
29 if model.existJointName(jn):
30 jointsToLockIDs.append(model.getJointId(jn))
32 print(
'Warning: joint ' + str(jn) +
' does not belong to the model!')
35 initialJointConfig = np.array([0,0,0,
39 model_reduced = pin.buildReducedModel(model, jointsToLockIDs, initialJointConfig)
42 model_reduced, visual_model_reduced = pin.buildReducedModel(
43 model, visual_model, jointsToLockIDs, initialJointConfig)
46 geom_models = [visual_model, collision_model]
47 model_reduced, geometric_models_reduced = pin.buildReducedModel(
49 list_of_geom_models=geom_models,
50 list_of_joints_to_lock=jointsToLockIDs,
51 reference_configuration=initialJointConfig)
53 visual_model_reduced, collision_model_reduced = geometric_models_reduced[
54 0], geometric_models_reduced[1]
58 print(
'joints to lock (only ids):', jointsToLockIDs)
59 print(
'reduced model: dim=' + str(len(model_reduced.joints)))
65 mixed_jointsToLockIDs = [jointsToLockIDs[0],
'wrist_2_joint',
'wrist_3_joint']
66 robot = pin.RobotWrapper.BuildFromURDF(urdf_filename, mesh_dir)
67 reduced_robot = robot.buildReducedRobot(list_of_joints_to_lock=mixed_jointsToLockIDs,
68 reference_configuration=initialJointConfig)
71 print(
'mixed joints to lock (names and ids):', mixed_jointsToLockIDs)
72 print(
'RobotWrapper reduced model: dim=' + str(len(reduced_robot.model.joints)))
73 for jn
in robot.model.joints: