build-reduced-model.py
Go to the documentation of this file.
1 from pathlib import Path
2 
3 import numpy as np
4 import pinocchio as pin
5 
6 # Goal: Build a reduced model from an existing URDF model by fixing the desired joints
7 # at a specified position.
8 
9 # Load UR robot arm
10 # This path refers to Pinocchio source code but you can define your own directory here.
11 pinocchio_model_dir = Path(__file__).parent.parent / "models"
12 model_path = pinocchio_model_dir / "example-robot-data/robots"
13 mesh_dir = pinocchio_model_dir
14 # You should change here to set up your own URDF file
15 urdf_filename = model_path / "ur_description/urdf/ur5_robot.urdf"
16 model, collision_model, visual_model = pin.buildModelsFromUrdf(urdf_filename, mesh_dir)
17 
18 # Check dimensions of the original model
19 print("standard model: dim=" + str(len(model.joints)))
20 for jn in model.joints:
21  print(jn)
22 print("-" * 30)
23 
24 # Create a list of joints to lock
25 jointsToLock = ["wrist_1_joint", "wrist_2_joint", "wrist_3_joint"]
26 
27 # Get the ID of all existing joints
28 jointsToLockIDs = []
29 for jn in jointsToLock:
30  if model.existJointName(jn):
31  jointsToLockIDs.append(model.getJointId(jn))
32  else:
33  print("Warning: joint " + str(jn) + " does not belong to the model!")
34 
35 # Set initial position of both fixed and revoulte joints
36 initialJointConfig = np.array(
37  [
38  0,
39  0,
40  0, # shoulder and elbow
41  1,
42  1,
43  1,
44  ]
45 ) # gripper)
46 
47 # Option 1: Only build the reduced model in case no display needed:
48 model_reduced = pin.buildReducedModel(model, jointsToLockIDs, initialJointConfig)
49 
50 # Option 2: Build the reduced model including the geometric model for proper displaying
51 # of the robot.
52 model_reduced, visual_model_reduced = pin.buildReducedModel(
53  model, visual_model, jointsToLockIDs, initialJointConfig
54 )
55 
56 # Option 3: Build the reduced model including multiple geometric models (for example:
57 # visuals, collision).
58 geom_models = [visual_model, collision_model]
59 model_reduced, geometric_models_reduced = pin.buildReducedModel(
60  model,
61  list_of_geom_models=geom_models,
62  list_of_joints_to_lock=jointsToLockIDs,
63  reference_configuration=initialJointConfig,
64 )
65 # geometric_models_reduced is a list, ordered as the passed variable "geom_models" so:
66 visual_model_reduced, collision_model_reduced = (
67  geometric_models_reduced[0],
68  geometric_models_reduced[1],
69 )
70 
71 # Check dimensions of the reduced model
72 # options 1-3 only take joint ids
73 print("joints to lock (only ids):", jointsToLockIDs)
74 print("reduced model: dim=" + str(len(model_reduced.joints)))
75 print("-" * 30)
76 
77 # Option 4: Build a reduced model of a robot using RobotWrapper
78 # reference_configuration is optional: if not provided, neutral configuration used
79 # you can even mix joint names and joint ids
80 mixed_jointsToLockIDs = [jointsToLockIDs[0], "wrist_2_joint", "wrist_3_joint"]
81 robot = pin.RobotWrapper.BuildFromURDF(urdf_filename, mesh_dir)
82 reduced_robot = robot.buildReducedRobot(
83  list_of_joints_to_lock=mixed_jointsToLockIDs,
84  reference_configuration=initialJointConfig,
85 )
86 
87 # Check dimensions of the reduced model and joint info
88 print("mixed joints to lock (names and ids):", mixed_jointsToLockIDs)
89 print("RobotWrapper reduced model: dim=" + str(len(reduced_robot.model.joints)))
90 for jn in robot.model.joints:
91  print(jn)


pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:25