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 | frameClassicAcceleration (self, index) |
def | frameClassicalAcceleration (self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL) |
def | frameJacobian (self, q, frame_id) |
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 | initDisplay (self, windowName="python-pinocchio", sceneName="world", loadModel=False) |
def | initFromURDF (self, filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None) |
def | initMeshcatDisplay (self, meshcat_visualizer, robot_name="pinocchio", robot_color=None) |
def | initViewer (self, share_data=True, args, kwargs) |
def | Jcom (self, q) |
def | jointJacobian (self, q, index) |
def | loadDisplayModel (self, rootNodeName="pinocchio") |
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 | BuildFromURDF (filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None) |
Public Attributes | |
collision_data | |
collision_model | |
data | |
model | |
q0 | |
v0 | |
visual_data | |
visual_model | |
viz | |
Definition at line 12 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.__init__ | ( | self, | |
model = pin.Model() , |
|||
collision_model = None , |
|||
visual_model = None , |
|||
verbose = False |
|||
) |
Definition at line 24 of file 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 115 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.acom | ( | self, | |
q, | |||
v, | |||
a | |||
) |
Definition at line 61 of file robot_wrapper.py.
|
static |
Definition at line 15 of file 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 180 of file 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 74 of file 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 68 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.centroidalMomentum | ( | self, | |
q, | |||
v | |||
) |
Definition at line 65 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.centroidalMomentumVariation | ( | self, | |
q, | |||
v, | |||
a | |||
) |
Definition at line 81 of file 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 120 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.com | ( | self, | |
q = None , |
|||
v = None , |
|||
a = None |
|||
) |
Definition at line 45 of file 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 227 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.computeJointJacobian | ( | self, | |
q, | |||
index | |||
) |
Definition at line 153 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.computeJointJacobians | ( | self, | |
q | |||
) |
Definition at line 159 of file 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.
Definition at line 326 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.displayCollisions | ( | self, | |
visibility | |||
) |
Set whether to diplay collision objects or not
Definition at line 330 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.displayVisuals | ( | self, | |
visibility | |||
) |
Set whether to diplay visual objects or not
Definition at line 334 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.forwardKinematics | ( | self, | |
q, | |||
v = None , |
|||
a = None |
|||
) |
Definition at line 96 of file 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 135 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.frameClassicAcceleration | ( | self, | |
index | |||
) |
Definition at line 146 of file 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 140 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.frameJacobian | ( | 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 220 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.framePlacement | ( | self, | |
q, | |||
index, | |||
update_kinematics = True |
|||
) |
Definition at line 125 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.framesForwardKinematics | ( | self, | |
q | |||
) |
Definition at line 175 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.frameVelocity | ( | self, | |
q, | |||
v, | |||
index, | |||
update_kinematics = True , |
|||
reference_frame = pin.ReferenceFrame.LOCAL |
|||
) |
Definition at line 130 of file 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 212 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.getJointJacobian | ( | self, | |
index, | |||
rf_frame = pin.ReferenceFrame.LOCAL |
|||
) |
Definition at line 156 of file 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 273 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.gravity | ( | self, | |
q | |||
) |
Definition at line 93 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.index | ( | self, | |
name | |||
) |
Definition at line 255 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.initDisplay | ( | self, | |
windowName = "python-pinocchio" , |
|||
sceneName = "world" , |
|||
loadModel = False |
|||
) |
Definition at line 300 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.initFromURDF | ( | self, | |
filename, | |||
package_dirs = None , |
|||
root_joint = None , |
|||
verbose = False , |
|||
meshLoader = None |
|||
) |
Definition at line 20 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.initMeshcatDisplay | ( | self, | |
meshcat_visualizer, | |||
robot_name = "pinocchio" , |
|||
robot_color = None |
|||
) |
Load the robot in a Meshcat viewer. Parameters: visualizer: the meshcat.Visualizer instance to use. robot_name: name to give to the robot in the viewer robot_color: optional, color to give to the robot. This overwrites the color present in the urdf. Format is a list of four RGBA floats (between 0 and 1)
Definition at line 304 of file robot_wrapper.py.
Init the viewer
Definition at line 277 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.Jcom | ( | self, | |
q | |||
) |
Definition at line 84 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.jointJacobian | ( | self, | |
q, | |||
index | |||
) |
Definition at line 150 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.loadDisplayModel | ( | self, | |
rootNodeName = "pinocchio" |
|||
) |
Create the scene displaying the robot meshes in gepetto-viewer
Definition at line 322 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.loadViewerModel | ( | self, | |
args, | |||
kwargs | |||
) |
Create the scene displaying the robot meshes in gepetto-viewer
Definition at line 317 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.mass | ( | self, | |
q | |||
) |
Definition at line 87 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.nle | ( | self, | |
q, | |||
v | |||
) |
Definition at line 90 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.nq | ( | self | ) |
Definition at line 38 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.nv | ( | self | ) |
Definition at line 42 of file robot_wrapper.py.
Definition at line 105 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.play | ( | self, | |
q_trajectory, | |||
dt | |||
) |
Play a trajectory with given time step
Definition at line 338 of file 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 234 of file 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 265 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.updateGeometryPlacements | ( | self, | |
q = None , |
|||
visual = False |
|||
) |
Definition at line 162 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.vcom | ( | self, | |
q, | |||
v | |||
) |
Definition at line 57 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.velocity | ( | self, | |
q, | |||
v, | |||
index, | |||
update_kinematics = True , |
|||
reference_frame = pin.ReferenceFrame.LOCAL |
|||
) |
Definition at line 110 of file robot_wrapper.py.
def pinocchio.robot_wrapper.RobotWrapper.viewer | ( | self | ) |
Definition at line 262 of file robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.collision_data |
Definition at line 250 of file robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.collision_model |
Definition at line 27 of file robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.data |
Definition at line 249 of file robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.model |
Definition at line 26 of file robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.q0 |
Definition at line 33 of file robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.v0 |
Definition at line 32 of file robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.visual_data |
Definition at line 30 of file robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.visual_model |
Definition at line 28 of file robot_wrapper.py.
pinocchio.robot_wrapper.RobotWrapper.viz |
Definition at line 35 of file robot_wrapper.py.