geometry-models.py
Go to the documentation of this file.
1 from pathlib import Path
2 from sys import argv
3 
4 import pinocchio
5 
6 # This path refers to Pinocchio source code but you can define your own directory here.
7 pinocchio_model_dir = Path(__file__).parent.parent / "models"
8 
9 model_path = Path(
10  (pinocchio_model_dir / "example-robot-data/robots") if len(argv) < 2 else argv[1]
11 )
12 mesh_dir = pinocchio_model_dir
13 urdf_model_path = model_path / "ur_description/urdf/ur5_robot.urdf"
14 
15 # Load the urdf model
16 model, collision_model, visual_model = pinocchio.buildModelsFromUrdf(
17  urdf_model_path, mesh_dir
18 )
19 print("model name: " + model.name)
20 
21 # Create data required by the algorithms
22 data, collision_data, visual_data = pinocchio.createDatas(
23  model, collision_model, visual_model
24 )
25 
26 # Sample a random configuration
28 print(f"q: {q.T}")
29 
30 # Perform the forward kinematics over the kinematic tree
31 pinocchio.forwardKinematics(model, data, q)
32 
33 # Update Geometry models
34 pinocchio.updateGeometryPlacements(model, data, collision_model, collision_data)
35 pinocchio.updateGeometryPlacements(model, data, visual_model, visual_data)
36 
37 # Print out the placement of each joint of the kinematic tree
38 print("\nJoint placements:")
39 for name, oMi in zip(model.names, data.oMi):
40  print("{:<24} : {: .2f} {: .2f} {: .2f}".format(name, *oMi.translation.T.flat))
41 
42 # Print out the placement of each collision geometry object
43 print("\nCollision object placements:")
44 for k, oMg in enumerate(collision_data.oMg):
45  print("{:d} : {: .2f} {: .2f} {: .2f}".format(k, *oMg.translation.T.flat))
46 
47 # Print out the placement of each visual geometry object
48 print("\nVisual object placements:")
49 for k, oMg in enumerate(visual_data.oMg):
50  print("{:d} : {: .2f} {: .2f} {: .2f}".format(k, *oMg.translation.T.flat))
pinocchio::updateGeometryPlacements
void updateGeometryPlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data)
Update the placement of the geometry objects according to the current joint placements contained in d...
pinocchio::randomConfiguration
void randomConfiguration(const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< ConfigOut_t > &qout)
pinocchio::forwardKinematics
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
Update the joint placements, spatial velocities and spatial accelerations according to the current jo...


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