5 from .
import pinocchio_pywrap
as pin
7 from .deprecation
import deprecated
8 from .shortcuts
import buildModelsFromUrdf, createDatas
15 def BuildFromURDF(filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None):
17 robot.initFromURDF(filename, package_dirs, root_joint, verbose, meshLoader)
20 def initFromURDF(self,filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None):
21 model, collision_model, visual_model =
buildModelsFromUrdf(filename, package_dirs, root_joint, verbose, meshLoader)
22 RobotWrapper.__init__(self,model=model,collision_model=collision_model,visual_model=visual_model)
24 def __init__(self, model = pin.Model(), collision_model =
None, visual_model =
None, verbose=
False):
32 self.
v0 = utils.zero(self.
nv)
45 def com(self, q=None, v=None, a=None):
47 pin.centerOfMass(self.
model, self.data)
48 return self.data.com[0]
51 pin.centerOfMass(self.
model, self.data, q, v)
52 return self.data.com[0], self.data.vcom[0]
53 pin.centerOfMass(self.
model, self.data, q, v, a)
54 return self.data.com[0], self.data.vcom[0], self.data.acom[0]
55 return pin.centerOfMass(self.
model, self.data, q)
58 pin.centerOfMass(self.
model, self.data, q, v)
59 return self.data.vcom[0]
62 pin.centerOfMass(self.
model, self.data, q, v, a)
63 return self.data.acom[0]
66 return pin.computeCentroidalMomentum(self.
model, self.data, q, v)
70 Computes the centroidal momentum matrix which maps from the joint velocity vector to the centroidal momentum expressed around the center of mass. 72 return pin.computeCentroidalMap(self.
model, self.data, q)
76 Computes all the quantities related to the centroidal dynamics (hg, Ag and Ig), corresponding to the centroidal momentum, the centroidal map and the centroidal rigid inertia. 78 pin.ccrba(self.
model, self.data, q, v)
79 return (self.data.hg, self.data.Ag, self.data.Ig)
82 return pin.computeCentroidalMomentumTimeVariation(self.
model, self.data, q, v, a)
85 return pin.jacobianCenterOfMass(self.
model, self.data, q)
88 return pin.crba(self.
model, self.data, q)
91 return pin.nonLinearEffects(self.
model, self.data, q, v)
94 return pin.computeGeneralizedGravity(self.
model, self.data, q)
99 pin.forwardKinematics(self.
model, self.data, q, v, a)
101 pin.forwardKinematics(self.
model, self.data, q, v)
103 pin.forwardKinematics(self.
model, self.data, q)
106 if update_kinematics:
107 pin.forwardKinematics(self.
model, self.data, q)
108 return self.data.oMi[index]
110 def velocity(self, q, v, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL):
111 if update_kinematics:
112 pin.forwardKinematics(self.
model, self.data, q, v)
113 return pin.getVelocity(self.
model, self.data, index, reference_frame)
115 def acceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL):
116 if update_kinematics:
117 pin.forwardKinematics(self.
model, self.data, q, v, a)
118 return pin.getAcceleration(self.
model, self.data, index, reference_frame)
121 if update_kinematics:
122 pin.forwardKinematics(self.
model, self.data, q, v, a)
123 return pin.getClassicalAcceleration(self.
model, self.data, index, reference_frame)
126 if update_kinematics:
127 pin.forwardKinematics(self.
model, self.data, q)
128 return pin.updateFramePlacement(self.
model, self.data, index)
130 def frameVelocity(self, q, v, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL):
131 if update_kinematics:
132 pin.forwardKinematics(self.
model, self.data, q, v)
133 return pin.getFrameVelocity(self.
model, self.data, index, reference_frame)
135 def frameAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL):
136 if update_kinematics:
137 pin.forwardKinematics(self.
model, self.data, q, v, a)
138 return pin.getFrameAcceleration(self.
model, self.data, index, reference_frame)
141 if update_kinematics:
142 pin.forwardKinematics(self.
model, self.data, q, v, a)
143 return pin.getFrameClassicalAcceleration(self.
model, self.data, index, reference_frame)
145 @
deprecated(
"This method has been replaced by frameClassicalAcceleration.")
149 @
deprecated(
"This method has been renamed computeJointJacobian. Please use computeJointJacobian instead of jointJacobian.")
151 return pin.computeJointJacobian(self.
model, self.data, q, index)
154 return pin.computeJointJacobian(self.
model, self.data, q, index)
157 return pin.getJointJacobian(self.
model, self.data, index, rf_frame)
160 return pin.computeJointJacobians(self.
model, self.data, q)
168 geom_data = self.collision_data
171 pin.updateGeometryPlacements(self.
model, self.data, geom_model, geom_data, q)
173 pin.updateGeometryPlacements(self.
model, self.data, geom_model, geom_data)
176 pin.framesForwardKinematics(self.
model, self.data, q)
179 list_of_joints_to_lock,
180 reference_configuration=
None):
182 Build a reduced robot model given a list of joints to lock. 184 \tlist_of_joints_to_lock: list of joint indexes/names to lock. 185 \treference_configuration: reference configuration to compute the 186 placement of the lock joints. If not provided, reference_configuration 187 defaults to the robot's neutral configuration. 189 Returns: a new robot model. 194 for jnt
in list_of_joints_to_lock:
196 if isinstance(jnt, str):
197 idx = self.model.getJointId(jnt)
198 lockjoints_idx.append(idx)
200 if reference_configuration
is None:
201 reference_configuration = pin.neutral(self.
model)
203 model, geom_models = pin.buildReducedModel(
206 list_of_joints_to_lock=lockjoints_idx,
207 reference_configuration=reference_configuration)
209 return RobotWrapper(model=model, visual_model=geom_models[0],
210 collision_model=geom_models[1])
214 It computes the Jacobian of frame given by its id (frame_id) either expressed in the 215 local coordinate frame or in the world coordinate frame. 217 return pin.getFrameJacobian(self.
model, self.data, frame_id, rf_frame)
219 @
deprecated(
"This method has been renamed computeFrameJacobian. Please use computeFrameJacobian instead of frameJacobian.")
222 Similar to getFrameJacobian but does not need pin.computeJointJacobians and 223 pin.updateFramePlacements to update internal value of self.data related to frames. 225 return pin.computeFrameJacobian(self.
model, self.data, q, frame_id)
229 Similar to getFrameJacobian but does not need pin.computeJointJacobians and 230 pin.updateFramePlacements to update internal value of self.data related to frames. 232 return pin.computeFrameJacobian(self.
model, self.data, q, frame_id)
235 """Re-build the data objects. Needed if the models were modified. 236 Warning: this will delete any information stored in all data objects.""" 238 if self.
viz is not None:
239 self.viz.rebuildData()
244 return self.model.getJointId(name)
251 return self.viz.viewer
254 """Set the visualizer. If init is True, the visualizer is initialized with this wrapper's models. 255 If copy_models is also True, the models are copied. Otherwise, they are simply kept as a reference. 259 self.
viz = visualizer
262 """For each geometry object, returns the corresponding name of the node in the display.""" 263 return self.viz.getViewerNodeName(geometry_object, geometry_type)
266 """Init the viewer""" 269 from .visualize
import GepettoVisualizer
272 self.viz.initViewer(*args, **kwargs)
275 def initDisplay(self, windowName="python-pinocchio", sceneName="world", loadModel=False):
276 self.
initViewer(windowName=windowName, sceneName=sceneName, loadModel=loadModel)
278 @
deprecated(
"You should manually set the visualizer, initialize it, and load the model.")
280 """ Load the robot in a Meshcat viewer. 282 visualizer: the meshcat.Visualizer instance to use. 283 robot_name: name to give to the robot in the viewer 284 robot_color: optional, color to give to the robot. This overwrites the color present in the urdf. 285 Format is a list of four RGBA floats (between 0 and 1) 287 from .visualize
import MeshcatVisualizer
289 self.viz.initViewer(meshcat_visualizer)
290 self.viz.loadViewerModel(rootNodeName=robot_name, color=robot_color)
293 """Create the scene displaying the robot meshes in gepetto-viewer""" 294 self.viz.loadViewerModel(*args, **kwargs)
298 """Create the scene displaying the robot meshes in gepetto-viewer""" 302 """Display the robot at configuration q in the viewer by placing all the bodies.""" 306 """Set whether to diplay collision objects or not""" 307 self.viz.displayCollisions(visibility)
310 """Set whether to diplay visual objects or not""" 311 self.viz.displayVisuals(visibility)
313 def play(self, q_trajectory, dt):
314 """Play a trajectory with given time step""" 315 self.viz.play(q_trajectory, dt)
317 __all__ = [
'RobotWrapper']
def acceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
def updateGeometryPlacements(self, q=None, visual=False)
def __init__(self, model=pin.Model(), collision_model=None, visual_model=None, verbose=False)
def computeJointJacobians(self, q)
def initViewer(self, args, kwargs)
def initMeshcatDisplay(self, meshcat_visualizer, robot_name="pinocchio", robot_color=None)
def frameClassicAcceleration(self, index)
def classicalAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
def getViewerNodeName(self, geometry_object, geometry_type)
def frameClassicalAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
def getFrameJacobian(self, frame_id, rf_frame=pin.ReferenceFrame.LOCAL)
def computeJointJacobian(self, q, index)
def buildModelsFromUrdf(filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None, geometry_types=[pin.GeometryType.COLLISION, pin, GeometryType, VISUAL)
def BuildFromURDF(filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None)
def frameAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
def centroidalMomentumVariation(self, q, v, a)
def framePlacement(self, q, index, update_kinematics=True)
def loadViewerModel(self, args, kwargs)
def com(self, q=None, v=None, a=None)
def frameJacobian(self, q, frame_id)
def initDisplay(self, windowName="python-pinocchio", sceneName="world", loadModel=False)
def forwardKinematics(self, q, v=None, a=None)
def initFromURDF(self, filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None)
def setVisualizer(self, visualizer, init=True, copy_models=False)
def frameVelocity(self, q, v, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
def displayVisuals(self, visibility)
def computeFrameJacobian(self, q, frame_id)
def displayCollisions(self, visibility)
def centroidalMap(self, q)
def play(self, q_trajectory, dt)
def deprecated(instructions)
def loadDisplayModel(self, rootNodeName="pinocchio")
def framesForwardKinematics(self, q)
def buildReducedRobot(self, list_of_joints_to_lock, reference_configuration=None)
def centroidalMomentum(self, q, v)
def centroidal(self, q, v)
def getJointJacobian(self, index, rf_frame=pin.ReferenceFrame.LOCAL)
def placement(self, q, index, update_kinematics=True)
def velocity(self, q, v, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
def jointJacobian(self, q, index)