frompathlibimportPathfromsysimportargvimportpinocchio# This path refers to Pinocchio source code but you can define your own directory here.pinocchio_model_dir=Path(__file__).parent.parent/"pinocchio"/"models"# You should change here to set up your own URDF file or just pass it as an argument of# this example.urdf_filename=(pinocchio_model_dir/"example-robot-data/robots/ur_description/urdf/ur5_robot.urdf"iflen(argv)<2elseargv[1])# Load the urdf modelmodel=pinocchio.buildModelFromUrdf(urdf_filename)print("model name: "+model.name)# Create data required by the algorithmsdata=model.createData()# Sample a random configurationq=pinocchio.randomConfiguration(model)print(f"q: {q.T}")# Perform the forward kinematics over the kinematic treepinocchio.forwardKinematics(model,data,q)# Print out the placement of each joint of the kinematic treeforname,oMiinzip(model.names,data.oMi):print("{:<24} : {: .2f}{: .2f}{: .2f}".format(name,*oMi.translation.T.flat))
Revolute joints, rotating around a fixed axis, either one of or a custom one;
Prismatic joints, translating along any fixed axis, as in the revolute case;
Spherical joints, free rotations in the 3D space;
Translation joints, for free translations in the 3D space;
Planar joints, for free movements in the 2D space;
Free-floating joints, for free movements in the 3D space. Planar and free-floating joints are meant to be employed as the basis of kinematic tree of mobile robots (humanoids, automated vehicles, or objects in manipulation planning).
Remark: In the URDF format, a joint of type fixed can be defined. However, a fixed joint is not really a joint because it cannot move. For efficiency reasons, it is therefore treated as operational frame of the model.
frompathlibimportPathimportsysimportpinocchioaspinimportnumpyasnpfrompinocchio.visualizeimportGepettoVisualizerpinocchio_model_dir=Path(__file__).parent.parent/'pinocchio'/"models"model_path=pinocchio_model_dir/"example-robot-data/robots"mesh_dir=pinocchio_model_dirurdf_filename="panda.urdf"urdf_model_path=model_path/"panda_description/urdf"/urdf_filenamemodel,collision_model,visual_model=pin.buildModelsFromUrdf(urdf_model_path,mesh_dir,pin.JointModelFreeFlyer())# # 如果urdf文件中的mesh是绝对路径,下面方法更简单一些# urdf_path = "../urdf/Franka_urdf/fr3_with_hand.urdf" # 正确的urdf路径# model: pin.Model = pin.buildModelFromUrdf(urdf_path)# visual_model = pin.buildGeomFromUrdf(model, urdf_path, pin.GeometryType.VISUAL)# collision_model = pin.buildGeomFromUrdf(model, urdf_path, pin.GeometryType.COLLISION)viz=GepettoVisualizer(model,collision_model,visual_model)# Initialize the viewer.try:viz.initViewer()exceptImportErroraserr:print("Error while initializing the viewer. ""It seems you should install gepetto-viewer")print(err)sys.exit(0)try:viz.loadViewerModel("pinocchio")exceptAttributeErroraserr:print("Error while loading the viewer model. ""It seems you should start gepetto-viewer")print(err)sys.exit(0)# Display a robot configuration.q0=pin.neutral(model)viz.display(q0)
importpinocchioaspinfrompathlibimportPathimportsysfrompinocchio.visualizeimportMeshcatVisualizerpinocchio_model_dir=Path(__file__).parent.parent/'pinocchio'/"models"model_path=pinocchio_model_dir/"example-robot-data/robots"mesh_dir=pinocchio_model_dirurdf_filename="panda.urdf"urdf_model_path=model_path/"panda_description/urdf"/urdf_filenamemodel,collision_model,visual_model=pin.buildModelsFromUrdf(urdf_model_path,mesh_dir,pin.JointModelFreeFlyer())# # 如果urdf文件中的mesh是绝对路径,下面方法更简单一些# urdf_path = "../urdf/Franka_urdf/fr3_with_hand.urdf" # 正确的urdf路径# model: pin.Model = pin.buildModelFromUrdf(urdf_path)# visual_model = pin.buildGeomFromUrdf(model, urdf_path, pin.GeometryType.VISUAL)# collision_model = pin.buildGeomFromUrdf(model, urdf_path, pin.GeometryType.COLLISION)try:viz=MeshcatVisualizer(model,collision_model,visual_model)viz.initViewer(open=True)exceptImportErroraserr:print("Error while initializing the viewer. ""It seems you should install Python meshcat")print(err)sys.exit(0)# Load the robot in the viewer.viz.loadViewerModel()# Display a robot configuration.q0=pin.neutral(model)viz.display(q0)viz.displayVisuals(True)input("Press Enter to continue...")# 没有这句话,显示就不对,很奇怪
# 创建model、datamodel:pin.Model=pin.buildModelFromUrdf(urdf_filename)data:pin.Data=model.createData()# 下面也是一种创建三种模型的方法,但是这个方法创建的model和model:pin.Model = pin.buildModelFromUrdf(urdf_filename)有点不太一样model,collision_model,visual_model=pin.buildModelsFromUrdf(urdf_model_path,mesh_dir,pin.JointModelFreeFlyer()# 还有下面两种,2024.12.14pin.buildModelFromXML()pin.buildModelFromMJCF()# 获得模型的自由度数model.nqmodel.nv# nq和nv可能会不一致,对于floating关节类型,就会不一致。# 得到关节的idJoint_id=model.getJointId("xxx")# 得到frame的id,也可以是固定关节(认为是frame)Frame_id=model.getFrameId("xxx")# 得到body的idbody_id=model.getBodyId("xxx")# 生成自然状态下q0=pin.neutral(model)# 生成随机状态的关节角度q_random=pin.randomConfiguration(model)# 获得全0的速度、加速度v=pinocchio.utils.zero(model.nv)a=pinocchio.utils.zero(model.nv)# 计算正运动学pin.forwardKinematics(model,data,q)# 优先用这个# pin.forwardKinematics(model, data, q, v)# pin.forwardKinematics(model, data, q, v, a)# Updates the position of each frame contained in the model.pin.updateFramePlacements(model,data)# 优先用这个# Updates the placement of the given frame.pin.updateFramePlacements(model,data,frame_id)pin.framesForwardKinematicsjoint_pose:pin.pinocchio_pywrap_default.SE3=data.oMi[joint_id]frame_pose:pin.pinocchio_pywrap_default.SE3=data.oMf[frame_id]# 上述的pose类型是:pinocchio.pinocchio_pywrap_default.SE3# 可用joint_pose.rotation得到旋转部分,joint_pose.translation得到平移部分final_joint_pose=data.oMi[-1]# 最后一个关节的pose# 计算、获的joint的jacobianJ=pin.computeJointJacobian(model,data,q,joint_id)# 计算、获得frame的jacobian# Computes the Jacobian of a specific Frame expressed in the LOCAL frame coordinate system.J=computeFrameJacobian(model,data,q,frame_id)# in the desired reference_frame given as argument.J=computeFrameJacobian(model,data,q,frame_id,reference_frame)pin.computeJointJacobians(model,data)pin.computeJointJacobians(model,data,q)# 优先用这个Jacobian=data.JJ=pin.getFrameJacobian(model,data,frame_id,reference_frame)J=pin.getJointJacobian(model,data,joint_id,reference_frame)# 计算动力学pin.forwardDynamics()pin.crba()# 计算动力学tau=pin.rnea(model,data,q,v,a)pin.computeCollision()pin.computeCollisions()pin.updateGeometryPlacements()pin.updateFramePlacement()pin.updateFramePlacements()pin.updateGlobalPlacements()pin.computeAllTermspin.ContactCholeskyDecompositionpin.integratepin.SE3.Identity()data.com[0]
# Print out the placement of each joint of the kinematic treeforname,oMiinzip(model.names,data.oMi):# *oMi.translation.T.flat展开位姿矩阵的平移部分(即关节的世界坐标位置)print(("{:<24} : {: .2f}{: .2f}{: .2f}".format(name,*oMi.translation.T.flat)))
This example shows how to position the end effector of a manipulator robot to a given pose (position and orientation). The example employs a simple Jacobian-based iterative algorithm, which is called closed-loop inverse kinematics (CLIK).
# 计算所有关节的雅可比矩阵,并且更新模型数据data结构中与每个关节相关的雅可比矩阵信息。in the world framepin.computeJointJacobians(model,data,q_random)# 必须先有这个,才能getprint("date.J: \n",data.J)# data.J默认是最后一个关节相对于0关节的Jacobian。# The result is accessible through data.J. # 这个函数也自动计算了forwardKinematics# pin.forwardKinematics(model, data, q_random),这个就不用写了
Planer joint,for free translations in the 2D space。
Free-floating joints,for free movements in the 3D space, Planar and free-floating joints are meant to be employed as the basis of kinematic tree of mobile robots(humanoids,automated vehicles,or objects in manipulation planning).