bindings/python/pinocchio/robot_wrapper.py
Go to the documentation of this file.
1 #
2 # Copyright (c) 2015-2020 CNRS INRIA
3 #
4 
5 from . import pinocchio_pywrap_default as pin
6 from . import utils
7 from .shortcuts import (
8  buildModelsFromMJCF,
9  buildModelsFromSdf,
10  buildModelsFromUrdf,
11  createDatas,
12 )
13 
14 
16  @staticmethod
17  def BuildFromURDF(filename, *args, **kwargs):
18  robot = RobotWrapper()
19 
20  robot.initFromURDF(filename, *args, **kwargs)
21 
22  return robot
23 
24  def initFromURDF(self, filename, *args, **kwargs):
25  model, collision_model, visual_model = buildModelsFromUrdf(
26  filename, *args, **kwargs
27  )
28 
29  RobotWrapper.__init__(
30  self,
31  model=model,
32  collision_model=collision_model,
33  visual_model=visual_model,
34  )
35 
36  @staticmethod
37  def BuildFromSDF(filename, *args, **kwargs):
38  robot = RobotWrapper()
39  robot.initFromSDF(filename, *args, **kwargs)
40  return robot
41 
42  def initFromSDF(self, filename, *args, **kwargs):
43  model, constraint_models, collision_model, visual_model = buildModelsFromSdf(
44  filename, *args, **kwargs
45  )
46 
47  RobotWrapper.__init__(
48  self,
49  model=model,
50  collision_model=collision_model,
51  visual_model=visual_model,
52  )
53  self.constraint_models = constraint_models
54 
55  @staticmethod
56  def BuildFromMJCF(filename, *args, **kwargs):
57  robot = RobotWrapper()
58  robot.initFromMJCF(filename, *args, **kwargs)
59 
60  return robot
61 
62  def initFromMJCF(self, filename, *args, **kwargs):
63  model, collision_model, visual_model = buildModelsFromMJCF(
64  filename, *args, **kwargs
65  )
66 
67  RobotWrapper.__init__(
68  self,
69  model=model,
70  collision_model=collision_model,
71  visual_model=visual_model,
72  )
73 
74  def __init__(
75  self, model=pin.Model(), collision_model=None, visual_model=None, verbose=False
76  ):
77  self.model = model
78  self.collision_model = collision_model
79  self.visual_model = visual_model
80 
81  self.data, self.collision_data, self.visual_data = createDatas(
82  model, collision_model, visual_model
83  )
84 
85  self.v0 = utils.zero(self.nv)
86  self.q0 = pin.neutral(self.model)
87 
88  self.viz = None
89 
90  @property
91  def nq(self):
92  return self.model.nq
93 
94  @property
95  def nv(self):
96  return self.model.nv
97 
98  def com(self, q=None, v=None, a=None):
99  if q is None:
100  pin.centerOfMass(self.model, self.data)
101  return self.data.com[0]
102  if v is not None:
103  if a is None:
104  pin.centerOfMass(self.model, self.data, q, v)
105  return self.data.com[0], self.data.vcom[0]
106  pin.centerOfMass(self.model, self.data, q, v, a)
107  return self.data.com[0], self.data.vcom[0], self.data.acom[0]
108  return pin.centerOfMass(self.model, self.data, q)
109 
110  def vcom(self, q, v):
111  pin.centerOfMass(self.model, self.data, q, v)
112  return self.data.vcom[0]
113 
114  def acom(self, q, v, a):
115  pin.centerOfMass(self.model, self.data, q, v, a)
116  return self.data.acom[0]
117 
118  def centroidalMomentum(self, q, v):
119  return pin.computeCentroidalMomentum(self.model, self.data, q, v)
120 
121  def centroidalMap(self, q):
122  """
123  Computes the centroidal momentum matrix which maps from the joint velocity
124  vector to the centroidal momentum expressed around the center of mass.
125  """
126  return pin.computeCentroidalMap(self.model, self.data, q)
127 
128  def centroidal(self, q, v):
129  """
130  Computes all the quantities related to the centroidal dynamics (hg, Ag and Ig),
131  corresponding to the centroidal momentum, the centroidal map and the centroidal
132  rigid inertia.
133  """
134  pin.ccrba(self.model, self.data, q, v)
135  return (self.data.hg, self.data.Ag, self.data.Ig)
136 
137  def centroidalMomentumVariation(self, q, v, a):
139  self.model, self.data, q, v, a
140  )
141 
142  def Jcom(self, q):
143  return pin.jacobianCenterOfMass(self.model, self.data, q)
144 
145  def mass(self, q):
146  return pin.crba(self.model, self.data, q)
147 
148  def nle(self, q, v):
149  return pin.nonLinearEffects(self.model, self.data, q, v)
150 
151  def gravity(self, q):
152  return pin.computeGeneralizedGravity(self.model, self.data, q)
153 
154  def forwardKinematics(self, q, v=None, a=None):
155  if v is not None:
156  if a is not None:
157  pin.forwardKinematics(self.model, self.data, q, v, a)
158  else:
159  pin.forwardKinematics(self.model, self.data, q, v)
160  else:
161  pin.forwardKinematics(self.model, self.data, q)
162 
163  def placement(self, q, index, update_kinematics=True):
164  if update_kinematics:
165  pin.forwardKinematics(self.model, self.data, q)
166  return self.data.oMi[index]
167 
168  def velocity(
169  self,
170  q,
171  v,
172  index,
173  update_kinematics=True,
174  reference_frame=pin.ReferenceFrame.LOCAL,
175  ):
176  if update_kinematics:
177  pin.forwardKinematics(self.model, self.data, q, v)
178  return pin.getVelocity(self.model, self.data, index, reference_frame)
179 
181  self,
182  q,
183  v,
184  a,
185  index,
186  update_kinematics=True,
187  reference_frame=pin.ReferenceFrame.LOCAL,
188  ):
189  if update_kinematics:
190  pin.forwardKinematics(self.model, self.data, q, v, a)
191  return pin.getAcceleration(self.model, self.data, index, reference_frame)
192 
194  self,
195  q,
196  v,
197  a,
198  index,
199  update_kinematics=True,
200  reference_frame=pin.ReferenceFrame.LOCAL,
201  ):
202  if update_kinematics:
203  pin.forwardKinematics(self.model, self.data, q, v, a)
205  self.model, self.data, index, reference_frame
206  )
207 
208  def framePlacement(self, q, index, update_kinematics=True):
209  if update_kinematics:
210  pin.forwardKinematics(self.model, self.data, q)
211  return pin.updateFramePlacement(self.model, self.data, index)
212 
214  self,
215  q,
216  v,
217  index,
218  update_kinematics=True,
219  reference_frame=pin.ReferenceFrame.LOCAL,
220  ):
221  if update_kinematics:
222  pin.forwardKinematics(self.model, self.data, q, v)
223  return pin.getFrameVelocity(self.model, self.data, index, reference_frame)
224 
226  self,
227  q,
228  v,
229  a,
230  index,
231  update_kinematics=True,
232  reference_frame=pin.ReferenceFrame.LOCAL,
233  ):
234  if update_kinematics:
235  pin.forwardKinematics(self.model, self.data, q, v, a)
236  return pin.getFrameAcceleration(self.model, self.data, index, reference_frame)
237 
239  self,
240  q,
241  v,
242  a,
243  index,
244  update_kinematics=True,
245  reference_frame=pin.ReferenceFrame.LOCAL,
246  ):
247  if update_kinematics:
248  pin.forwardKinematics(self.model, self.data, q, v, a)
250  self.model, self.data, index, reference_frame
251  )
252 
253  def computeJointJacobian(self, q, index):
254  return pin.computeJointJacobian(self.model, self.data, q, index)
255 
256  def getJointJacobian(self, index, rf_frame=pin.ReferenceFrame.LOCAL):
257  return pin.getJointJacobian(self.model, self.data, index, rf_frame)
258 
259  def computeJointJacobians(self, q):
260  return pin.computeJointJacobians(self.model, self.data, q)
261 
262  def updateGeometryPlacements(self, q=None, visual=False):
263  if visual:
264  geom_model = self.visual_model
265  geom_data = self.visual_data
266  else:
267  geom_model = self.collision_model
268  geom_data = self.collision_data
269 
270  if q is not None:
272  self.model, self.data, geom_model, geom_data, q
273  )
274  else:
275  pin.updateGeometryPlacements(self.model, self.data, geom_model, geom_data)
276 
278  pin.framesForwardKinematics(self.model, self.data, q)
279 
280  def buildReducedRobot(self, list_of_joints_to_lock, reference_configuration=None):
281  """
282  Build a reduced robot model given a list of joints to lock.
283  Parameters:
284  \tlist_of_joints_to_lock: list of joint indexes/names to lock.
285  \treference_configuration: reference configuration to compute the
286  placement of the lock joints. If not provided, reference_configuration
287  defaults to the robot's neutral configuration.
288 
289  Returns: a new robot model.
290  """
291 
292  # if joint to lock is a string, try to find its index
293  lockjoints_idx = []
294  for jnt in list_of_joints_to_lock:
295  idx = jnt
296  if isinstance(jnt, str):
297  idx = self.model.getJointId(jnt)
298  lockjoints_idx.append(idx)
299 
300  if reference_configuration is None:
301  reference_configuration = pin.neutral(self.model)
302 
303  model, geom_models = pin.buildReducedModel(
304  model=self.model,
305  list_of_geom_models=[self.visual_model, self.collision_model],
306  list_of_joints_to_lock=lockjoints_idx,
307  reference_configuration=reference_configuration,
308  )
309 
310  return RobotWrapper(
311  model=model, visual_model=geom_models[0], collision_model=geom_models[1]
312  )
313 
314  def getFrameJacobian(self, frame_id, rf_frame=pin.ReferenceFrame.LOCAL):
315  """
316  It computes the Jacobian of frame given by its id (frame_id) either expressed in
317  the local coordinate frame or in the world coordinate frame.
318  """
319  return pin.getFrameJacobian(self.model, self.data, frame_id, rf_frame)
320 
321  def computeFrameJacobian(self, q, frame_id):
322  """
323  Similar to getFrameJacobian but does not need pin.computeJointJacobians and
324  pin.updateFramePlacements to update internal value of self.data related to
325  frames.
326  """
327  return pin.computeFrameJacobian(self.model, self.data, q, frame_id)
328 
329  def rebuildData(self):
330  """Re-build the data objects. Needed if the models were modified.
331  Warning: this will delete any information stored in all data objects."""
332  data, collision_data, visual_data = createDatas(
333  self.model, self.collision_model, self.visual_model
334  )
335  if self.viz is not None:
336  if (
337  id(self.data) == id(self.viz.data)
338  and id(self.collision_data) == id(self.viz.collision_data)
339  and id(self.visual_data) == id(self.viz.visual_data)
340  ):
341  self.viz.data = data
342  self.viz.collision_data = collision_data
343  self.viz.visual_data = visual_data
344  else:
345  self.viz.rebuildData()
346  self.data = data
347  self.collision_data = collision_data
348  self.visual_data = visual_data
349 
350  # --- ACCESS TO NAMES ----
351  # Return the index of the joint whose name is given in argument.
352  def index(self, name):
353  return self.model.getJointId(name)
354 
355  # --- VIEWER ---
356 
357  # for backwards compatibility
358  @property
359  def viewer(self):
360  return self.viz.viewer
361 
362  def setVisualizer(self, visualizer, init=True, copy_models=False):
363  """
364  Set the visualizer. If init is True, the visualizer is initialized with this
365  wrapper's models. If copy_models is also True, the models are copied.
366  Otherwise, they are simply kept as a reference.
367  """
368  if init:
369  visualizer.__init__(
370  self.model, self.collision_model, self.visual_model, copy_models
371  )
372  self.viz = visualizer
373 
374  def getViewerNodeName(self, geometry_object, geometry_type):
375  """
376  For each geometry object, returns the corresponding name of the node in the
377  display.
378  """
379  return self.viz.getViewerNodeName(geometry_object, geometry_type)
380 
381  def initViewer(self, share_data=True, *args, **kwargs):
382  """Init the viewer"""
383  # Set viewer to use to MeshCat.
384  if self.viz is None:
385  from .visualize import Visualizer
386 
387  data, collision_data, visual_data = None, None, None
388  if share_data:
389  data = self.data
390  collision_data = self.collision_data
391  visual_data = self.visual_data
392  self.viz = Visualizer.default()(
393  self.model,
394  self.collision_model,
395  self.visual_model,
396  not share_data,
397  data,
398  collision_data,
399  visual_data,
400  )
401 
402  self.viz.initViewer(*args, **kwargs)
403 
404  def loadViewerModel(self, *args, **kwargs):
405  """Create the scene displaying the robot meshes in MeshCat"""
406  self.viz.loadViewerModel(*args, **kwargs)
407 
408  def display(self, q):
409  """
410  Display the robot at configuration q in the viewer by placing all the bodies.
411  """
412  self.viz.display(q)
413 
414  def displayCollisions(self, visibility):
415  """Set whether to diplay collision objects or not"""
416  self.viz.displayCollisions(visibility)
417 
418  def displayVisuals(self, visibility):
419  """Set whether to diplay visual objects or not"""
420  self.viz.displayVisuals(visibility)
421 
422  def play(self, q_trajectory, dt):
423  """Play a trajectory with given time step"""
424  self.viz.play(q_trajectory, dt)
425 
426 
427 __all__ = ["RobotWrapper"]
pinocchio.robot_wrapper.RobotWrapper.nq
def nq(self)
Definition: bindings/python/pinocchio/robot_wrapper.py:91
pinocchio.robot_wrapper.RobotWrapper.__init__
def __init__(self, model=pin.Model(), collision_model=None, visual_model=None, verbose=False)
Definition: bindings/python/pinocchio/robot_wrapper.py:74
pinocchio.robot_wrapper.RobotWrapper.play
def play(self, q_trajectory, dt)
Definition: bindings/python/pinocchio/robot_wrapper.py:422
pinocchio.robot_wrapper.RobotWrapper.BuildFromSDF
def BuildFromSDF(filename, *args, **kwargs)
Definition: bindings/python/pinocchio/robot_wrapper.py:37
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.robot_wrapper.RobotWrapper.computeJointJacobian
def computeJointJacobian(self, q, index)
Definition: bindings/python/pinocchio/robot_wrapper.py:253
pinocchio.robot_wrapper.RobotWrapper.constraint_models
constraint_models
Definition: bindings/python/pinocchio/robot_wrapper.py:53
pinocchio::getFrameClassicalAcceleration
MotionTpl< Scalar, Options > getFrameClassicalAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
Returns the "classical" acceleration of the Frame expressed in the desired reference frame....
Definition: frames.hpp:225
pinocchio.robot_wrapper.RobotWrapper.frameVelocity
def frameVelocity(self, q, v, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
Definition: bindings/python/pinocchio/robot_wrapper.py:213
pinocchio.robot_wrapper.RobotWrapper.Jcom
def Jcom(self, q)
Definition: bindings/python/pinocchio/robot_wrapper.py:142
pinocchio.robot_wrapper.RobotWrapper.initViewer
def initViewer(self, share_data=True, *args, **kwargs)
Definition: bindings/python/pinocchio/robot_wrapper.py:381
pinocchio.robot_wrapper.RobotWrapper.acom
def acom(self, q, v, a)
Definition: bindings/python/pinocchio/robot_wrapper.py:114
pinocchio.robot_wrapper.RobotWrapper.index
def index(self, name)
Definition: bindings/python/pinocchio/robot_wrapper.py:352
pinocchio.robot_wrapper.RobotWrapper
Definition: bindings/python/pinocchio/robot_wrapper.py:15
pinocchio.robot_wrapper.RobotWrapper.centroidalMomentumVariation
def centroidalMomentumVariation(self, q, v, a)
Definition: bindings/python/pinocchio/robot_wrapper.py:137
pinocchio.shortcuts.buildModelsFromUrdf
tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] buildModelsFromUrdf(filename, *args, **kwargs)
Definition: shortcuts.py:14
pinocchio::id
JointIndex id(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdVisitor to get the index of the joint in the kinematic chain.
pinocchio.robot_wrapper.RobotWrapper.velocity
def velocity(self, q, v, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
Definition: bindings/python/pinocchio/robot_wrapper.py:168
pinocchio.robot_wrapper.RobotWrapper.getViewerNodeName
def getViewerNodeName(self, geometry_object, geometry_type)
Definition: bindings/python/pinocchio/robot_wrapper.py:374
pinocchio.robot_wrapper.RobotWrapper.computeJointJacobians
def computeJointJacobians(self, q)
Definition: bindings/python/pinocchio/robot_wrapper.py:259
pinocchio.robot_wrapper.RobotWrapper.placement
def placement(self, q, index, update_kinematics=True)
Definition: bindings/python/pinocchio/robot_wrapper.py:163
pinocchio::getJointJacobian
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame)
Computes the Jacobian of a specific joint frame expressed either in the world (rf = WORLD) frame,...
Definition: jacobian.hpp:127
pinocchio::getFrameAcceleration
MotionTpl< Scalar, Options > getFrameAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
Returns the spatial acceleration of the Frame expressed in the desired reference frame....
Definition: frames.hpp:165
pinocchio.robot_wrapper.RobotWrapper.setVisualizer
def setVisualizer(self, visualizer, init=True, copy_models=False)
Definition: bindings/python/pinocchio/robot_wrapper.py:362
pinocchio::crba
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Convention convention=Convention::LOCAL)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
pinocchio.robot_wrapper.RobotWrapper.nv
def nv(self)
Definition: bindings/python/pinocchio/robot_wrapper.py:95
pinocchio.robot_wrapper.RobotWrapper.buildReducedRobot
def buildReducedRobot(self, list_of_joints_to_lock, reference_configuration=None)
Definition: bindings/python/pinocchio/robot_wrapper.py:280
pinocchio.robot_wrapper.RobotWrapper.v0
v0
Definition: bindings/python/pinocchio/robot_wrapper.py:83
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.robot_wrapper.RobotWrapper.visual_model
visual_model
Definition: bindings/python/pinocchio/robot_wrapper.py:77
pinocchio.robot_wrapper.RobotWrapper.acceleration
def acceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
Definition: bindings/python/pinocchio/robot_wrapper.py:180
pinocchio.robot_wrapper.RobotWrapper.frameAcceleration
def frameAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
Definition: bindings/python/pinocchio/robot_wrapper.py:225
pinocchio.robot_wrapper.RobotWrapper.loadViewerModel
def loadViewerModel(self, *args, **kwargs)
Definition: bindings/python/pinocchio/robot_wrapper.py:404
pinocchio.shortcuts.createDatas
def createDatas(*models)
Definition: shortcuts.py:119
pinocchio.robot_wrapper.RobotWrapper.getJointJacobian
def getJointJacobian(self, index, rf_frame=pin.ReferenceFrame.LOCAL)
Definition: bindings/python/pinocchio/robot_wrapper.py:256
pinocchio.shortcuts.buildModelsFromSdf
tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] buildModelsFromSdf(filename, *args, **kwargs)
Definition: shortcuts.py:128
pinocchio::getFrameVelocity
MotionTpl< Scalar, Options > getFrameVelocity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
Returns the spatial velocity of the Frame expressed in the desired reference frame....
Definition: frames.hpp:107
pinocchio.robot_wrapper.RobotWrapper.mass
def mass(self, q)
Definition: bindings/python/pinocchio/robot_wrapper.py:145
pinocchio.robot_wrapper.RobotWrapper.com
def com(self, q=None, v=None, a=None)
Definition: bindings/python/pinocchio/robot_wrapper.py:98
pinocchio.robot_wrapper.RobotWrapper.data
data
Definition: bindings/python/pinocchio/robot_wrapper.py:346
pinocchio::computeCentroidalMap
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeCentroidalMap(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the Centroidal Momentum Matrix.
pinocchio.robot_wrapper.RobotWrapper.BuildFromMJCF
def BuildFromMJCF(filename, *args, **kwargs)
Definition: bindings/python/pinocchio/robot_wrapper.py:56
pinocchio.robot_wrapper.RobotWrapper.viewer
def viewer(self)
Definition: bindings/python/pinocchio/robot_wrapper.py:359
pinocchio.robot_wrapper.RobotWrapper.displayCollisions
def displayCollisions(self, visibility)
Definition: bindings/python/pinocchio/robot_wrapper.py:414
pinocchio.robot_wrapper.RobotWrapper.vcom
def vcom(self, q, v)
Definition: bindings/python/pinocchio/robot_wrapper.py:110
pinocchio.robot_wrapper.RobotWrapper.classicalAcceleration
def classicalAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
Definition: bindings/python/pinocchio/robot_wrapper.py:193
pinocchio.robot_wrapper.RobotWrapper.framePlacement
def framePlacement(self, q, index, update_kinematics=True)
Definition: bindings/python/pinocchio/robot_wrapper.py:208
pinocchio::ccrba
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & ccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Centroidal Momentum Matrix, the Composite Ridig Body Inertia as well as the centroidal m...
pinocchio.robot_wrapper.RobotWrapper.BuildFromURDF
def BuildFromURDF(filename, *args, **kwargs)
Definition: bindings/python/pinocchio/robot_wrapper.py:17
pinocchio.robot_wrapper.RobotWrapper.getFrameJacobian
def getFrameJacobian(self, frame_id, rf_frame=pin.ReferenceFrame.LOCAL)
Definition: bindings/python/pinocchio/robot_wrapper.py:314
pinocchio.robot_wrapper.RobotWrapper.viz
viz
Definition: bindings/python/pinocchio/robot_wrapper.py:86
pinocchio.robot_wrapper.RobotWrapper.centroidalMomentum
def centroidalMomentum(self, q, v)
Definition: bindings/python/pinocchio/robot_wrapper.py:118
pinocchio.robot_wrapper.RobotWrapper.q0
q0
Definition: bindings/python/pinocchio/robot_wrapper.py:84
pinocchio::nonLinearEffects
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & nonLinearEffects(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the non-linear effects (Corriolis, centrifual and gravitationnal effects),...
display
Definition: display.py:1
pinocchio::computeFrameJacobian
void computeFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frame_id, const Eigen::MatrixBase< Matrix6xLike > &J)
Computes the Jacobian of a specific Frame expressed in the LOCAL frame coordinate system.
Definition: frames.hpp:475
pinocchio::framesForwardKinematics
void framesForwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
First calls the forwardKinematics on the model, then computes the placement of each frame....
pinocchio::neutral
Eigen::Matrix< typename LieGroupCollection::Scalar, Eigen::Dynamic, 1, LieGroupCollection::Options > neutral(const LieGroupGenericTpl< LieGroupCollection > &lg)
Visit a LieGroupVariant to get the neutral element of it.
pinocchio.robot_wrapper.RobotWrapper.visual_data
visual_data
Definition: bindings/python/pinocchio/robot_wrapper.py:79
pinocchio.robot_wrapper.RobotWrapper.collision_model
collision_model
Definition: bindings/python/pinocchio/robot_wrapper.py:76
pinocchio::getVelocity
MotionTpl< Scalar, Options > getVelocity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
Returns the spatial velocity of the joint expressed in the desired reference frame....
pinocchio::centerOfMass
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & centerOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
Computes the center of mass position, velocity and acceleration of a given model according to the cur...
Definition: center-of-mass.hpp:194
pinocchio.robot_wrapper.RobotWrapper.computeFrameJacobian
def computeFrameJacobian(self, q, frame_id)
Definition: bindings/python/pinocchio/robot_wrapper.py:321
pinocchio.robot_wrapper.RobotWrapper.initFromMJCF
def initFromMJCF(self, filename, *args, **kwargs)
Definition: bindings/python/pinocchio/robot_wrapper.py:62
pinocchio::computeJointJacobians
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the world frame....
pinocchio::jacobianCenterOfMass
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & jacobianCenterOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
Computes both the jacobian and the the center of mass position of a given model according to the curr...
pinocchio.robot_wrapper.RobotWrapper.initFromSDF
def initFromSDF(self, filename, *args, **kwargs)
Definition: bindings/python/pinocchio/robot_wrapper.py:42
pinocchio.robot_wrapper.RobotWrapper.initFromURDF
def initFromURDF(self, filename, *args, **kwargs)
Definition: bindings/python/pinocchio/robot_wrapper.py:24
pinocchio.robot_wrapper.RobotWrapper.rebuildData
def rebuildData(self)
Definition: bindings/python/pinocchio/robot_wrapper.py:329
pinocchio.robot_wrapper.RobotWrapper.displayVisuals
def displayVisuals(self, visibility)
Definition: bindings/python/pinocchio/robot_wrapper.py:418
pinocchio::getFrameJacobian
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > getFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame reference_frame)
Returns the jacobian of the frame expressed either expressed in the local frame coordinate system,...
Definition: frames.hpp:394
pinocchio::computeCentroidalMomentumTimeVariation
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalMomentumTimeVariation(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)
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and...
pinocchio.robot_wrapper.RobotWrapper.gravity
def gravity(self, q)
Definition: bindings/python/pinocchio/robot_wrapper.py:151
pinocchio.robot_wrapper.RobotWrapper.centroidal
def centroidal(self, q, v)
Definition: bindings/python/pinocchio/robot_wrapper.py:128
pinocchio::computeJointJacobian
void computeJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex joint_id, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store t...
pinocchio::getClassicalAcceleration
MotionTpl< Scalar, Options > getClassicalAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
Returns the "classical" acceleration of the joint expressed in the desired reference frame....
pinocchio.robot_wrapper.RobotWrapper.collision_data
collision_data
Definition: bindings/python/pinocchio/robot_wrapper.py:347
pinocchio.robot_wrapper.RobotWrapper.framesForwardKinematics
def framesForwardKinematics(self, q)
Definition: bindings/python/pinocchio/robot_wrapper.py:277
pinocchio.robot_wrapper.RobotWrapper.forwardKinematics
def forwardKinematics(self, q, v=None, a=None)
Definition: bindings/python/pinocchio/robot_wrapper.py:154
pinocchio.robot_wrapper.RobotWrapper.frameClassicalAcceleration
def frameClassicalAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
Definition: bindings/python/pinocchio/robot_wrapper.py:238
pinocchio.robot_wrapper.RobotWrapper.display
def display(self, q)
Definition: bindings/python/pinocchio/robot_wrapper.py:408
pinocchio::updateFramePlacement
const DataTpl< Scalar, Options, JointCollectionTpl >::SE3 & updateFramePlacement(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id)
Updates the placement of the given frame.
pinocchio::buildReducedModel
void buildReducedModel(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::vector< GeometryModel, GeometryModelAllocator > &list_of_geom_models, const std::vector< JointIndex > &list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration, ModelTpl< Scalar, Options, JointCollectionTpl > &reduced_model, std::vector< GeometryModel, GeometryModelAllocator > &list_of_reduced_geom_models)
Build a reduced model and a rededuced geometry model from a given input model, a given input geometry...
pinocchio::computeCentroidalMomentum
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalMomentum(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Centroidal momentum, a.k.a. the total momenta of the system expressed around the center ...
pinocchio::getAcceleration
MotionTpl< Scalar, Options > getAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
Returns the spatial acceleration of the joint expressed in the desired reference frame....
pinocchio.robot_wrapper.RobotWrapper.model
model
Definition: bindings/python/pinocchio/robot_wrapper.py:75
pinocchio.robot_wrapper.RobotWrapper.updateGeometryPlacements
def updateGeometryPlacements(self, q=None, visual=False)
Definition: bindings/python/pinocchio/robot_wrapper.py:262
pinocchio::computeGeneralizedGravity
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & computeGeneralizedGravity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the generalized gravity contribution of the Lagrangian dynamics:
pinocchio.robot_wrapper.RobotWrapper.centroidalMap
def centroidalMap(self, q)
Definition: bindings/python/pinocchio/robot_wrapper.py:121
pinocchio.robot_wrapper.RobotWrapper.nle
def nle(self, q, v)
Definition: bindings/python/pinocchio/robot_wrapper.py:148
pinocchio.shortcuts.buildModelsFromMJCF
def buildModelsFromMJCF(filename, *args, **kwargs)
Definition: shortcuts.py:240


pinocchio
Author(s):
autogenerated on Wed May 28 2025 02:41:21