Public Member Functions | |
def | __init__ (self, model=pin.Model(), collision_model=None, visual_model=None, verbose=False) |
def | acceleration (self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL) |
def | acom (self, q, v, a) |
def | buildReducedRobot (self, list_of_joints_to_lock, reference_configuration=None) |
def | centroidal (self, q, v) |
def | centroidalMap (self, q) |
def | centroidalMomentum (self, q, v) |
def | centroidalMomentumVariation (self, q, v, a) |
def | classicalAcceleration (self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL) |
def | com (self, q=None, v=None, a=None) |
def | computeFrameJacobian (self, q, frame_id) |
def | computeJointJacobian (self, q, index) |
def | computeJointJacobians (self, q) |
def | display (self, q) |
def | displayCollisions (self, visibility) |
def | displayVisuals (self, visibility) |
def | forwardKinematics (self, q, v=None, a=None) |
def | frameAcceleration (self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL) |
def | frameClassicalAcceleration (self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL) |
def | framePlacement (self, q, index, update_kinematics=True) |
def | framesForwardKinematics (self, q) |
def | frameVelocity (self, q, v, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL) |
def | getFrameJacobian (self, frame_id, rf_frame=pin.ReferenceFrame.LOCAL) |
def | getJointJacobian (self, index, rf_frame=pin.ReferenceFrame.LOCAL) |
def | getViewerNodeName (self, geometry_object, geometry_type) |
def | gravity (self, q) |
def | index (self, name) |
def | initFromMJCF (self, filename, *args, **kwargs) |
def | initFromSDF (self, filename, *args, **kwargs) |
def | initFromURDF (self, filename, *args, **kwargs) |
def | initViewer (self, share_data=True, *args, **kwargs) |
def | Jcom (self, q) |
def | loadViewerModel (self, *args, **kwargs) |
def | mass (self, q) |
def | nle (self, q, v) |
def | nq (self) |
def | nv (self) |
def | placement (self, q, index, update_kinematics=True) |
def | play (self, q_trajectory, dt) |
def | rebuildData (self) |
def | setVisualizer (self, visualizer, init=True, copy_models=False) |
def | updateGeometryPlacements (self, q=None, visual=False) |
def | vcom (self, q, v) |
def | velocity (self, q, v, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL) |
def | viewer (self) |
Static Public Member Functions | |
def | BuildFromMJCF (filename, *args, **kwargs) |
def | BuildFromSDF (filename, *args, **kwargs) |
def | BuildFromURDF (filename, *args, **kwargs) |
Public Attributes | |
collision_data | |
collision_model | |
constraint_models | |
data | |
model | |
q0 | |
v0 | |
visual_data | |
visual_model | |
viz | |
Definition at line 15 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.__init__ | ( | self, | |
model = pin.Model() , |
|||
collision_model = None , |
|||
visual_model = None , |
|||
verbose = False |
|||
) |
Definition at line 74 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.acceleration | ( | self, | |
q, | |||
v, | |||
a, | |||
index, | |||
update_kinematics = True , |
|||
reference_frame = pin.ReferenceFrame.LOCAL |
|||
) |
Definition at line 180 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.acom | ( | self, | |
q, | |||
v, | |||
a | |||
) |
Definition at line 114 of file bindings/python/pinocchio/robot_wrapper.py.
|
static |
Definition at line 56 of file bindings/python/pinocchio/robot_wrapper.py.
|
static |
Definition at line 37 of file bindings/python/pinocchio/robot_wrapper.py.
|
static |
Definition at line 17 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.buildReducedRobot | ( | self, | |
list_of_joints_to_lock, | |||
reference_configuration = None |
|||
) |
Build a reduced robot model given a list of joints to lock. Parameters: \tlist_of_joints_to_lock: list of joint indexes/names to lock. \treference_configuration: reference configuration to compute the placement of the lock joints. If not provided, reference_configuration defaults to the robot's neutral configuration. Returns: a new robot model.
Definition at line 280 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.centroidal | ( | self, | |
q, | |||
v | |||
) |
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.
Definition at line 128 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.centroidalMap | ( | self, | |
q | |||
) |
Computes the centroidal momentum matrix which maps from the joint velocity vector to the centroidal momentum expressed around the center of mass.
Definition at line 121 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.centroidalMomentum | ( | self, | |
q, | |||
v | |||
) |
Definition at line 118 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.centroidalMomentumVariation | ( | self, | |
q, | |||
v, | |||
a | |||
) |
Definition at line 137 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.classicalAcceleration | ( | self, | |
q, | |||
v, | |||
a, | |||
index, | |||
update_kinematics = True , |
|||
reference_frame = pin.ReferenceFrame.LOCAL |
|||
) |
Definition at line 193 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.com | ( | self, | |
q = None , |
|||
v = None , |
|||
a = None |
|||
) |
Definition at line 98 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.computeFrameJacobian | ( | self, | |
q, | |||
frame_id | |||
) |
Similar to getFrameJacobian but does not need pin.computeJointJacobians and pin.updateFramePlacements to update internal value of self.data related to frames.
Definition at line 321 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.computeJointJacobian | ( | self, | |
q, | |||
index | |||
) |
Definition at line 253 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.computeJointJacobians | ( | self, | |
q | |||
) |
Definition at line 259 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.display | ( | self, | |
q | |||
) |
Display the robot at configuration q in the viewer by placing all the bodies.
Reimplemented in mobilerobot.MobileRobotWrapper.
Definition at line 408 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.displayCollisions | ( | self, | |
visibility | |||
) |
Set whether to diplay collision objects or not
Definition at line 414 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.displayVisuals | ( | self, | |
visibility | |||
) |
Set whether to diplay visual objects or not
Definition at line 418 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.forwardKinematics | ( | self, | |
q, | |||
v = None , |
|||
a = None |
|||
) |
Definition at line 154 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.frameAcceleration | ( | self, | |
q, | |||
v, | |||
a, | |||
index, | |||
update_kinematics = True , |
|||
reference_frame = pin.ReferenceFrame.LOCAL |
|||
) |
Definition at line 225 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.frameClassicalAcceleration | ( | self, | |
q, | |||
v, | |||
a, | |||
index, | |||
update_kinematics = True , |
|||
reference_frame = pin.ReferenceFrame.LOCAL |
|||
) |
Definition at line 238 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.framePlacement | ( | self, | |
q, | |||
index, | |||
update_kinematics = True |
|||
) |
Definition at line 208 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.framesForwardKinematics | ( | self, | |
q | |||
) |
Definition at line 277 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.frameVelocity | ( | self, | |
q, | |||
v, | |||
index, | |||
update_kinematics = True , |
|||
reference_frame = pin.ReferenceFrame.LOCAL |
|||
) |
Definition at line 213 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.getFrameJacobian | ( | self, | |
frame_id, | |||
rf_frame = pin.ReferenceFrame.LOCAL |
|||
) |
It computes the Jacobian of frame given by its id (frame_id) either expressed in the local coordinate frame or in the world coordinate frame.
Definition at line 314 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.getJointJacobian | ( | self, | |
index, | |||
rf_frame = pin.ReferenceFrame.LOCAL |
|||
) |
Definition at line 256 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.getViewerNodeName | ( | self, | |
geometry_object, | |||
geometry_type | |||
) |
For each geometry object, returns the corresponding name of the node in the display.
Definition at line 374 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.gravity | ( | self, | |
q | |||
) |
Definition at line 151 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.index | ( | self, | |
name | |||
) |
Definition at line 352 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.initFromMJCF | ( | self, | |
filename, | |||
* | args, | ||
** | kwargs | ||
) |
Definition at line 62 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.initFromSDF | ( | self, | |
filename, | |||
* | args, | ||
** | kwargs | ||
) |
Definition at line 42 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.initFromURDF | ( | self, | |
filename, | |||
* | args, | ||
** | kwargs | ||
) |
Definition at line 24 of file bindings/python/pinocchio/robot_wrapper.py.
Init the viewer
Definition at line 381 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.Jcom | ( | self, | |
q | |||
) |
Definition at line 142 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.loadViewerModel | ( | self, | |
* | args, | ||
** | kwargs | ||
) |
Create the scene displaying the robot meshes in MeshCat
Definition at line 404 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.mass | ( | self, | |
q | |||
) |
Definition at line 145 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.nle | ( | self, | |
q, | |||
v | |||
) |
Definition at line 148 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.nq | ( | self | ) |
Definition at line 91 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.nv | ( | self | ) |
Definition at line 95 of file bindings/python/pinocchio/robot_wrapper.py.
Definition at line 163 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.play | ( | self, | |
q_trajectory, | |||
dt | |||
) |
Play a trajectory with given time step
Definition at line 422 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.rebuildData | ( | self | ) |
Re-build the data objects. Needed if the models were modified. Warning: this will delete any information stored in all data objects.
Definition at line 329 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.setVisualizer | ( | self, | |
visualizer, | |||
init = True , |
|||
copy_models = False |
|||
) |
Set the visualizer. If init is True, the visualizer is initialized with this wrapper's models. If copy_models is also True, the models are copied. Otherwise, they are simply kept as a reference.
Definition at line 362 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.updateGeometryPlacements | ( | self, | |
q = None , |
|||
visual = False |
|||
) |
Definition at line 262 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.vcom | ( | self, | |
q, | |||
v | |||
) |
Definition at line 110 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.velocity | ( | self, | |
q, | |||
v, | |||
index, | |||
update_kinematics = True , |
|||
reference_frame = pin.ReferenceFrame.LOCAL |
|||
) |
Definition at line 168 of file bindings/python/pinocchio/robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.viewer | ( | self | ) |
Definition at line 359 of file bindings/python/pinocchio/robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.collision_data |
Definition at line 347 of file bindings/python/pinocchio/robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.collision_model |
Definition at line 76 of file bindings/python/pinocchio/robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.constraint_models |
Definition at line 53 of file bindings/python/pinocchio/robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.data |
Definition at line 346 of file bindings/python/pinocchio/robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.model |
Definition at line 75 of file bindings/python/pinocchio/robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.q0 |
Definition at line 84 of file bindings/python/pinocchio/robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.v0 |
Definition at line 83 of file bindings/python/pinocchio/robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.visual_data |
Definition at line 79 of file bindings/python/pinocchio/robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.visual_model |
Definition at line 77 of file bindings/python/pinocchio/robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.viz |
Definition at line 86 of file bindings/python/pinocchio/robot_wrapper.py.