overview-urdf.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 # You should change here to set up your own URDF file or just pass it as an argument of
10 # this example.
11 urdf_filename = (
12  pinocchio_model_dir / "example-robot-data/robots/ur_description/urdf/ur5_robot.urdf"
13  if len(argv) < 2
14  else argv[1]
15 )
16 
17 # Load the urdf model
18 model = pinocchio.buildModelFromUrdf(urdf_filename)
19 print("model name: " + model.name)
20 
21 # Create data required by the algorithms
22 data = model.createData()
23 
24 # Sample a random configuration
26 print(f"q: {q.T}")
27 
28 # Perform the forward kinematics over the kinematic tree
29 pinocchio.forwardKinematics(model, data, q)
30 
31 # Print out the placement of each joint of the kinematic tree
32 for name, oMi in zip(model.names, data.oMi):
33  print("{:<24} : {: .2f} {: .2f} {: .2f}".format(name, *oMi.translation.T.flat))
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 Sun Dec 22 2024 03:41:12