1 from pathlib 
import Path
 
    4 import pinocchio 
as pin
 
   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
 
   15 urdf_filename = model_path / 
"ur_description/urdf/ur5_robot.urdf" 
   16 model, collision_model, visual_model = pin.buildModelsFromUrdf(urdf_filename, mesh_dir)
 
   19 print(
"standard model: dim=" + str(len(model.joints)))
 
   20 for jn 
in model.joints:
 
   25 jointsToLock = [
"wrist_1_joint", 
"wrist_2_joint", 
"wrist_3_joint"]
 
   29 for jn 
in jointsToLock:
 
   30     if model.existJointName(jn):
 
   31         jointsToLockIDs.append(model.getJointId(jn))
 
   33         print(
"Warning: joint " + str(jn) + 
" does not belong to the model!")
 
   36 initialJointConfig = np.array(
 
   53     model, visual_model, jointsToLockIDs, initialJointConfig
 
   58 geom_models = [visual_model, collision_model]
 
   61     list_of_geom_models=geom_models,
 
   62     list_of_joints_to_lock=jointsToLockIDs,
 
   63     reference_configuration=initialJointConfig,
 
   66 visual_model_reduced, collision_model_reduced = (
 
   67     geometric_models_reduced[0],
 
   68     geometric_models_reduced[1],
 
   73 print(
"joints to lock (only ids):", jointsToLockIDs)
 
   74 print(
"reduced model: dim=" + str(len(model_reduced.joints)))
 
   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,
 
   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: