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 as pin
6 from . import utils
7 from .deprecation import deprecated
8 from .shortcuts import buildModelsFromUrdf, createDatas
9 
10 import numpy as np
11 
12 class RobotWrapper(object):
13 
14  @staticmethod
15  def BuildFromURDF(filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None):
16  robot = RobotWrapper()
17  robot.initFromURDF(filename, package_dirs, root_joint, verbose, meshLoader)
18  return robot
19 
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)
23 
24  def __init__(self, model = pin.Model(), collision_model = None, visual_model = None, verbose=False):
25 
26  self.model = model
27  self.collision_model = collision_model
28  self.visual_model = visual_model
29 
30  self.data, self.collision_data, self.visual_data = createDatas(model,collision_model,visual_model)
31 
32  self.v0 = utils.zero(self.nv)
33  self.q0 = pin.neutral(self.model)
34 
35  self.viz = None
36 
37  @property
38  def nq(self):
39  return self.model.nq
40 
41  @property
42  def nv(self):
43  return self.model.nv
44 
45  def com(self, q=None, v=None, a=None):
46  if q is None:
47  pin.centerOfMass(self.model, self.data)
48  return self.data.com[0]
49  if v is not None:
50  if a is None:
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)
56 
57  def vcom(self, q, v):
58  pin.centerOfMass(self.model, self.data, q, v)
59  return self.data.vcom[0]
60 
61  def acom(self, q, v, a):
62  pin.centerOfMass(self.model, self.data, q, v, a)
63  return self.data.acom[0]
64 
65  def centroidalMomentum(self, q, v):
66  return pin.computeCentroidalMomentum(self.model, self.data, q, v)
67 
68  def centroidalMap(self, q):
69  '''
70  Computes the centroidal momentum matrix which maps from the joint velocity vector to the centroidal momentum expressed around the center of mass.
71  '''
72  return pin.computeCentroidalMap(self.model, self.data, q)
73 
74  def centroidal(self, q, v):
75  '''
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.
77  '''
78  pin.ccrba(self.model, self.data, q, v)
79  return (self.data.hg, self.data.Ag, self.data.Ig)
80 
81  def centroidalMomentumVariation(self, q, v, a):
82  return pin.computeCentroidalMomentumTimeVariation(self.model, self.data, q, v, a)
83 
84  def Jcom(self, q):
85  return pin.jacobianCenterOfMass(self.model, self.data, q)
86 
87  def mass(self, q):
88  return pin.crba(self.model, self.data, q)
89 
90  def nle(self, q, v):
91  return pin.nonLinearEffects(self.model, self.data, q, v)
92 
93  def gravity(self, q):
94  return pin.computeGeneralizedGravity(self.model, self.data, q)
95 
96  def forwardKinematics(self, q, v=None, a=None):
97  if v is not None:
98  if a is not None:
99  pin.forwardKinematics(self.model, self.data, q, v, a)
100  else:
101  pin.forwardKinematics(self.model, self.data, q, v)
102  else:
103  pin.forwardKinematics(self.model, self.data, q)
104 
105  def placement(self, q, index, update_kinematics=True):
106  if update_kinematics:
107  pin.forwardKinematics(self.model, self.data, q)
108  return self.data.oMi[index]
109 
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)
114 
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)
119 
120  def classicalAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL):
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)
124 
125  def framePlacement(self, q, index, update_kinematics=True):
126  if update_kinematics:
127  pin.forwardKinematics(self.model, self.data, q)
128  return pin.updateFramePlacement(self.model, self.data, index)
129 
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)
134 
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)
139 
140  def frameClassicalAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL):
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)
144 
145  @deprecated("This method has been replaced by frameClassicalAcceleration.")
146  def frameClassicAcceleration(self, index):
147  return self.frameClassicalAcceleration(None, None, None, index, False)
148 
149  @deprecated("This method has been renamed computeJointJacobian. Please use computeJointJacobian instead of jointJacobian.")
150  def jointJacobian(self, q, index):
151  return pin.computeJointJacobian(self.model, self.data, q, index)
152 
153  def computeJointJacobian(self, q, index):
154  return pin.computeJointJacobian(self.model, self.data, q, index)
155 
156  def getJointJacobian(self, index, rf_frame=pin.ReferenceFrame.LOCAL):
157  return pin.getJointJacobian(self.model, self.data, index, rf_frame)
158 
159  def computeJointJacobians(self, q):
160  return pin.computeJointJacobians(self.model, self.data, q)
161 
162  def updateGeometryPlacements(self, q=None, visual=False):
163  if visual:
164  geom_model = self.visual_model
165  geom_data = self.visual_data
166  else:
167  geom_model = self.collision_model
168  geom_data = self.collision_data
169 
170  if q is not None:
171  pin.updateGeometryPlacements(self.model, self.data, geom_model, geom_data, q)
172  else:
173  pin.updateGeometryPlacements(self.model, self.data, geom_model, geom_data)
174 
176  pin.framesForwardKinematics(self.model, self.data, q)
177 
178  def buildReducedRobot(self,
179  list_of_joints_to_lock,
180  reference_configuration=None):
181  """
182  Build a reduced robot model given a list of joints to lock.
183  Parameters:
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.
188 
189  Returns: a new robot model.
190  """
191 
192  # if joint to lock is a string, try to find its index
193  lockjoints_idx = []
194  for jnt in list_of_joints_to_lock:
195  idx = jnt
196  if isinstance(jnt, str):
197  idx = self.model.getJointId(jnt)
198  lockjoints_idx.append(idx)
199 
200  if reference_configuration is None:
201  reference_configuration = pin.neutral(self.model)
202 
203  model, geom_models = pin.buildReducedModel(
204  model=self.model,
205  list_of_geom_models=[self.visual_model, self.collision_model],
206  list_of_joints_to_lock=lockjoints_idx,
207  reference_configuration=reference_configuration)
208 
209  return RobotWrapper(model=model, visual_model=geom_models[0],
210  collision_model=geom_models[1])
211 
212  def getFrameJacobian(self, frame_id, rf_frame=pin.ReferenceFrame.LOCAL):
213  """
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.
216  """
217  return pin.getFrameJacobian(self.model, self.data, frame_id, rf_frame)
218 
219  @deprecated("This method has been renamed computeFrameJacobian. Please use computeFrameJacobian instead of frameJacobian.")
220  def frameJacobian(self, q, frame_id):
221  """
222  Similar to getFrameJacobian but does not need pin.computeJointJacobians and
223  pin.updateFramePlacements to update internal value of self.data related to frames.
224  """
225  return pin.computeFrameJacobian(self.model, self.data, q, frame_id)
226 
227  def computeFrameJacobian(self, q, frame_id):
228  """
229  Similar to getFrameJacobian but does not need pin.computeJointJacobians and
230  pin.updateFramePlacements to update internal value of self.data related to frames.
231  """
232  return pin.computeFrameJacobian(self.model, self.data, q, frame_id)
233 
234  def rebuildData(self):
235  """Re-build the data objects. Needed if the models were modified.
236  Warning: this will delete any information stored in all data objects."""
237  self.data, self.collision_data, self.visual_data = createDatas(self.model, self.collision_model, self.visual_model)
238  if self.viz is not None:
239  self.viz.rebuildData()
240 
241  # --- ACCESS TO NAMES ----
242  # Return the index of the joint whose name is given in argument.
243  def index(self, name):
244  return self.model.getJointId(name)
245 
246  # --- VIEWER ---
247 
248  # for backwards compatibility
249  @property
250  def viewer(self):
251  return self.viz.viewer
252 
253  def setVisualizer(self, visualizer, init=True, copy_models=False):
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.
256  """
257  if init:
258  visualizer.__init__(self.model, self.collision_model, self.visual_model, copy_models)
259  self.viz = visualizer
260 
261  def getViewerNodeName(self, geometry_object, geometry_type):
262  """For each geometry object, returns the corresponding name of the node in the display."""
263  return self.viz.getViewerNodeName(geometry_object, geometry_type)
264 
265  def initViewer(self, *args, **kwargs):
266  """Init the viewer"""
267  # Set viewer to use to gepetto-gui.
268  if self.viz is None:
269  from .visualize import GepettoVisualizer
270  self.viz = GepettoVisualizer(self.model, self.collision_model, self.visual_model)
271 
272  self.viz.initViewer(*args, **kwargs)
273 
274  @deprecated("Use initViewer")
275  def initDisplay(self, windowName="python-pinocchio", sceneName="world", loadModel=False):
276  self.initViewer(windowName=windowName, sceneName=sceneName, loadModel=loadModel)
277 
278  @deprecated("You should manually set the visualizer, initialize it, and load the model.")
279  def initMeshcatDisplay(self, meshcat_visualizer, robot_name = "pinocchio", robot_color = None):
280  """ Load the robot in a Meshcat viewer.
281  Parameters:
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)
286  """
287  from .visualize import MeshcatVisualizer
288  self.viz = MeshcatVisualizer(self.model, self.collision_model, self.visual_model)
289  self.viz.initViewer(meshcat_visualizer)
290  self.viz.loadViewerModel(rootNodeName=robot_name, color=robot_color)
291 
292  def loadViewerModel(self, *args, **kwargs):
293  """Create the scene displaying the robot meshes in gepetto-viewer"""
294  self.viz.loadViewerModel(*args, **kwargs)
295 
296  @deprecated("Use loadViewerModel")
297  def loadDisplayModel(self, rootNodeName="pinocchio"):
298  """Create the scene displaying the robot meshes in gepetto-viewer"""
299  self.loadViewerModel(rootNodeName=rootNodeName)
300 
301  def display(self, q):
302  """Display the robot at configuration q in the viewer by placing all the bodies."""
303  self.viz.display(q)
304 
305  def displayCollisions(self,visibility):
306  """Set whether to diplay collision objects or not"""
307  self.viz.displayCollisions(visibility)
308 
309  def displayVisuals(self,visibility):
310  """Set whether to diplay visual objects or not"""
311  self.viz.displayVisuals(visibility)
312 
313  def play(self, q_trajectory, dt):
314  """Play a trajectory with given time step"""
315  self.viz.play(q_trajectory, dt)
316 
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 initViewer(self, args, kwargs)
def initMeshcatDisplay(self, meshcat_visualizer, robot_name="pinocchio", robot_color=None)
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 createDatas(models)
Definition: shortcuts.py:52
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)
Definition: shortcuts.py:12
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 play(self, q_trajectory, dt)
def deprecated(instructions)
Definition: deprecation.py:7
def loadDisplayModel(self, rootNodeName="pinocchio")
def buildReducedRobot(self, list_of_joints_to_lock, reference_configuration=None)
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)


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:04