Frame

class Frame

A Plucker coordinate frame related to a parent joint inside a kinematic tree.

cast((Frame)arg1) Frame :

Returns a cast of *this.

copy((Frame)self) Frame :

Returns a copy of *this.

property inertia

Inertia information attached to the frame.

property name

name of the frame

property parent

See parentJoint property.

property parentFrame

Index of the parent frame

property parentJoint

Index of the parent joint

property placement

placement in the parent joint local frame

property previousFrame

See parentFrame property.

property type

type of the frame

computeFrameJacobian((Model)model, (Data)data, (numpy.ndarray)q, (int)frame_id, (ReferenceFrame)reference_frame) numpy.ndarray :

Computes the Jacobian of the frame given by its frame_id in the coordinate system given by reference_frame.

computeFrameJacobian((Model)model, (Data)data, (numpy.ndarray)q, (int)frame_id) numpy.ndarray :

Computes the Jacobian of the frame given by its frame_id. The columns of the Jacobian are expressed in the coordinates system of the Frame itself. In other words, the velocity of the frame vF expressed in the local coordinate is given by J*v,where v is the joint velocity.

computeSupportedForceByFrame((Model)model, (Data)data, (int)frame_id) Force :

Computes the supported force of the frame (given by frame_id) and returns it. The supported force corresponds to the sum of all the forces experienced after the given frame. You must first call pinocchio::rnea to update placement values in data structure.

computeSupportedInertiaByFrame((Model)model, (Data)data, (int)frame_id, (bool)with_subtree) Inertia :

Computes the supported inertia by the frame (given by frame_id) and returns it. The supported inertia corresponds to the sum of the inertias of all the child frames (that belongs to the same joint body) and the child joints, if with_subtree=True. You must first call pinocchio::forwardKinematics to update placement values in data structure.

frameJacobianTimeVariation((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (int)frame_id, (ReferenceFrame)reference_frame) numpy.ndarray :

Computes the Jacobian Time Variation of the frame given by its frame_id either in the reference frame provided by reference_frame.

framesForwardKinematics((Model)model, (Data)data, (numpy.ndarray)q) None :

Calls first the forwardKinematics(model,data,q) and then update the Frame placement quantities (data.oMf).

getFrameAcceleration((Model)model, (Data)data, (int)frame_id[, (ReferenceFrame)reference_frame=pinocchio.pinocchio_pywrap_default.ReferenceFrame.LOCAL]) Motion :

Returns the spatial acceleration of the frame expressed in the coordinate system given by reference_frame. forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial acceleration stored in data.a.

getFrameAcceleration((Model)model, (Data)data, (int)joint_id, (SE3)placement[, (ReferenceFrame)reference_frame=pinocchio.pinocchio_pywrap_default.ReferenceFrame.LOCAL]) Motion :

Returns the spatial acceleration of the frame expressed in the coordinate system given by reference_frame. forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial acceleration stored in data.a .

getFrameAccelerationDerivatives((Model)model, (Data)data, (int)frame_id, (ReferenceFrame)reference_frame) tuple :

Computes the partial derivatives of the spatial acceleration of a given frame with respect to the joint configuration, velocity and acceleration and returns them as a tuple. The partial derivatives can be either expressed in the LOCAL frame of the joint, in the LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of reference_frame. You must first call computeForwardKinematicsDerivatives before calling this function.

Parameters:
  • model – model of the kinematic tree

  • data – data related to the model

  • frame_id – index of the frame

  • reference_frame – reference frame in which the resulting derivatives are expressed

getFrameAccelerationDerivatives((Model)model, (Data)data, (int)joint_id, (SE3)placement, (ReferenceFrame)reference_frame) tuple :

Computes the partial derivatives of the spatial acceleration of a frame given by its relative placement, with respect to the joint configuration, velocity and acceleration and returns them as a tuple. The partial derivatives can be either expressed in the LOCAL frame of the joint, in the LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of reference_frame. You must first call computeForwardKinematicsDerivatives before calling this function.

Parameters:
  • model – model of the kinematic tree

  • data – data related to the model

  • joint_id – index of the joint

  • placement – placement of the Frame w.r.t. the joint frame.

  • reference_frame – reference frame in which the resulting derivatives are expressed

getFrameClassicalAcceleration((Model)model, (Data)data, (int)frame_id[, (ReferenceFrame)reference_frame=pinocchio.pinocchio_pywrap_default.ReferenceFrame.LOCAL]) Motion :

Returns the “classical” acceleration of the frame expressed in the coordinate system given by reference_frame. forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial acceleration stored in data.a .

getFrameClassicalAcceleration((Model)model, (Data)data, (int)joint_id, (SE3)placement[, (ReferenceFrame)reference_frame=pinocchio.pinocchio_pywrap_default.ReferenceFrame.LOCAL]) Motion :

Returns the “classical” acceleration of the frame expressed in the coordinate system given by reference_frame. forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial acceleration stored in data.a .

getFrameJacobian((Model)model, (Data)data, (int)frame_id, (ReferenceFrame)reference_frame) numpy.ndarray :

Computes the Jacobian of the frame given by its ID either in the LOCAL, LOCAL_WORLD_ALIGNED or the WORLD coordinates systems. In other words, the velocity of the frame vF expressed in the reference frame is given by J*v,where v is the joint velocity vector. remarks: computeJointJacobians(model,data,q) must have been called first.

getFrameJacobian((Model)model, (Data)data, (int)joint_id, (SE3)placement, (ReferenceFrame)reference_frame) numpy.ndarray :

Computes the Jacobian of the frame given by its placement with respect to the Joint frame and expressed the solution either in the LOCAL, LOCAL_WORLD_ALIGNED or the WORLD coordinates systems. In other words, the velocity of the frame vF expressed in the reference frame is given by J*v,where v is the joint velocity vector.

remarks: computeJointJacobians(model,data,q) must have been called first.

getFrameJacobianTimeVariation((Model)model, (Data)data, (int)frame_id, (ReferenceFrame)reference_frame) numpy.ndarray :

Returns the Jacobian time variation of the frame given by its frame_id either in the reference frame provided by reference_frame. You have to call computeJointJacobiansTimeVariation(model,data,q,v) and updateFramePlacements(model,data) first.

getFrameVelocity((Model)model, (Data)data, (int)frame_id[, (ReferenceFrame)reference_frame=pinocchio.pinocchio_pywrap_default.ReferenceFrame.LOCAL]) Motion :

Returns the spatial velocity of the frame expressed in the coordinate system given by reference_frame. forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint spatial velocity stored in data.v

getFrameVelocity((Model)model, (Data)data, (int)joint_id, (SE3)placement[, (ReferenceFrame)reference_frame=pinocchio.pinocchio_pywrap_default.ReferenceFrame.LOCAL]) Motion :

Returns the spatial velocity of the frame expressed in the coordinate system given by reference_frame. forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint spatial velocity stored in data.v

getFrameVelocityDerivatives((Model)model, (Data)data, (int)frame_id, (ReferenceFrame)reference_frame) tuple :

Computes the partial derivatives of the spatial velocity of a given frame with respect to the joint configuration and velocity and returns them as a tuple. The partial derivatives can be either expressed in the LOCAL frame of the joint, in the LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of reference_frame. You must first call computeForwardKinematicsDerivatives before calling this function.

Parameters:
  • model – model of the kinematic tree

  • data – data related to the model

  • frame_id – index of the frame

  • reference_frame – reference frame in which the resulting derivatives are expressed

getFrameVelocityDerivatives((Model)model, (Data)data, (int)joint_id, (SE3)placement, (ReferenceFrame)reference_frame) tuple :

Computes the partial derivatives of the spatial velocity of a frame given by its relative placement, with respect to the joint configuration and velocity and returns them as a tuple. The partial derivatives can be either expressed in the LOCAL frame of the joint, in the LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of reference_frame. You must first call computeForwardKinematicsDerivatives before calling this function.

Parameters:
  • model – model of the kinematic tree

  • data – data related to the model

  • joint_id – index of the joint

  • placement – placement of the Frame w.r.t. the joint frame.

  • reference_frame – reference frame in which the resulting derivatives are expressed

updateFramePlacement((Model)model, (Data)data, (int)frame_id) SE3 :

Computes the placement of the given operational frame (frame_id) according to the current joint placement stored in data, stores the results in data and returns it.

updateFramePlacements((Model)model, (Data)data) None :

Computes the placements of all the operational frames according to the current joint placement stored in dataand puts the results in data.