5 from .
import pinocchio_pywrap_default
as pin
7 from .shortcuts
import (
20 robot.initFromURDF(filename, *args, **kwargs)
26 filename, *args, **kwargs
29 RobotWrapper.__init__(
32 collision_model=collision_model,
33 visual_model=visual_model,
39 robot.initFromSDF(filename, *args, **kwargs)
44 filename, *args, **kwargs
47 RobotWrapper.__init__(
50 collision_model=collision_model,
51 visual_model=visual_model,
58 robot.initFromMJCF(filename, *args, **kwargs)
64 filename, *args, **kwargs
67 RobotWrapper.__init__(
70 collision_model=collision_model,
71 visual_model=visual_model,
75 self, model=pin.Model(), collision_model=
None, visual_model=
None, verbose=
False
82 model, collision_model, visual_model
85 self.
v0 = utils.zero(self.
nv)
98 def com(self, q=None, v=None, a=None):
101 return self.
data.com[0]
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)
111 pin.centerOfMass(self.
model, self.
data, q, v)
112 return self.
data.vcom[0]
115 pin.centerOfMass(self.
model, self.
data, q, v, a)
116 return self.
data.acom[0]
119 return pin.computeCentroidalMomentum(self.
model, self.
data, q, v)
123 Computes the centroidal momentum matrix which maps from the joint velocity
124 vector to the centroidal momentum expressed around the center of mass.
126 return pin.computeCentroidalMap(self.
model, self.
data, q)
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
138 return pin.computeCentroidalMomentumTimeVariation(
143 return pin.jacobianCenterOfMass(self.
model, self.
data, q)
146 return pin.crba(self.
model, self.
data, q)
149 return pin.nonLinearEffects(self.
model, self.
data, q, v)
152 return pin.computeGeneralizedGravity(self.
model, self.
data, q)
157 pin.forwardKinematics(self.
model, self.
data, q, v, a)
159 pin.forwardKinematics(self.
model, self.
data, q, v)
161 pin.forwardKinematics(self.
model, self.
data, q)
164 if update_kinematics:
165 pin.forwardKinematics(self.
model, self.
data, q)
166 return self.
data.oMi[index]
173 update_kinematics=True,
174 reference_frame=pin.ReferenceFrame.LOCAL,
176 if update_kinematics:
177 pin.forwardKinematics(self.
model, self.
data, q, v)
178 return pin.getVelocity(self.
model, self.
data, index, reference_frame)
186 update_kinematics=True,
187 reference_frame=pin.ReferenceFrame.LOCAL,
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)
199 update_kinematics=True,
200 reference_frame=pin.ReferenceFrame.LOCAL,
202 if update_kinematics:
203 pin.forwardKinematics(self.
model, self.
data, q, v, a)
204 return pin.getClassicalAcceleration(
205 self.
model, self.
data, index, reference_frame
209 if update_kinematics:
210 pin.forwardKinematics(self.
model, self.
data, q)
211 return pin.updateFramePlacement(self.
model, self.
data, index)
218 update_kinematics=True,
219 reference_frame=pin.ReferenceFrame.LOCAL,
221 if update_kinematics:
222 pin.forwardKinematics(self.
model, self.
data, q, v)
223 return pin.getFrameVelocity(self.
model, self.
data, index, reference_frame)
231 update_kinematics=True,
232 reference_frame=pin.ReferenceFrame.LOCAL,
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)
244 update_kinematics=True,
245 reference_frame=pin.ReferenceFrame.LOCAL,
247 if update_kinematics:
248 pin.forwardKinematics(self.
model, self.
data, q, v, a)
249 return pin.getFrameClassicalAcceleration(
250 self.
model, self.
data, index, reference_frame
254 return pin.computeJointJacobian(self.
model, self.
data, q, index)
257 return pin.getJointJacobian(self.
model, self.
data, index, rf_frame)
260 return pin.computeJointJacobians(self.
model, self.
data, q)
271 pin.updateGeometryPlacements(
272 self.
model, self.
data, geom_model, geom_data, q
275 pin.updateGeometryPlacements(self.
model, self.
data, geom_model, geom_data)
278 pin.framesForwardKinematics(self.
model, self.
data, q)
282 Build a reduced robot model given a list of joints to lock.
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.
289 Returns: a new robot model.
294 for jnt
in list_of_joints_to_lock:
296 if isinstance(jnt, str):
297 idx = self.
model.getJointId(jnt)
298 lockjoints_idx.append(idx)
300 if reference_configuration
is None:
301 reference_configuration = pin.neutral(self.
model)
303 model, geom_models = pin.buildReducedModel(
306 list_of_joints_to_lock=lockjoints_idx,
307 reference_configuration=reference_configuration,
311 model=model, visual_model=geom_models[0], collision_model=geom_models[1]
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.
319 return pin.getFrameJacobian(self.
model, self.
data, frame_id, rf_frame)
323 Similar to getFrameJacobian but does not need pin.computeJointJacobians and
324 pin.updateFramePlacements to update internal value of self.data related to
327 return pin.computeFrameJacobian(self.
model, self.
data, q, frame_id)
330 """Re-build the data objects. Needed if the models were modified.
331 Warning: this will delete any information stored in all data objects."""
335 if self.
viz is not None:
342 self.
viz.collision_data = collision_data
343 self.
viz.visual_data = visual_data
353 return self.
model.getJointId(name)
360 return self.
viz.viewer
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.
372 self.
viz = visualizer
376 For each geometry object, returns the corresponding name of the node in the
382 """Init the viewer"""
385 from .visualize
import Visualizer
387 data, collision_data, visual_data =
None,
None,
None
392 self.
viz = Visualizer.default()(
405 """Create the scene displaying the robot meshes in MeshCat"""
410 Display the robot at configuration q in the viewer by placing all the bodies.
415 """Set whether to diplay collision objects or not"""
419 """Set whether to diplay visual objects or not"""
422 def play(self, q_trajectory, dt):
423 """Play a trajectory with given time step"""
424 self.
viz.
play(q_trajectory, dt)
427 __all__ = [
"RobotWrapper"]