Go to the documentation of this file.
    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]
 
  105                 return self.
data.com[0], self.
data.vcom[0]
 
  107             return self.
data.com[0], self.
data.vcom[0], self.
data.acom[0]
 
  112         return self.
data.vcom[0]
 
  116         return self.
data.acom[0]
 
  123         Computes the centroidal momentum matrix which maps from the joint velocity 
  124         vector to the centroidal momentum expressed around the center of mass. 
  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 
  164         if update_kinematics:
 
  166         return self.
data.oMi[index]
 
  173         update_kinematics=True,
 
  174         reference_frame=pin.ReferenceFrame.LOCAL,
 
  176         if update_kinematics:
 
  186         update_kinematics=True,
 
  187         reference_frame=pin.ReferenceFrame.LOCAL,
 
  189         if update_kinematics:
 
  199         update_kinematics=True,
 
  200         reference_frame=pin.ReferenceFrame.LOCAL,
 
  202         if update_kinematics:
 
  205             self.
model, self.
data, index, reference_frame
 
  209         if update_kinematics:
 
  218         update_kinematics=True,
 
  219         reference_frame=pin.ReferenceFrame.LOCAL,
 
  221         if update_kinematics:
 
  231         update_kinematics=True,
 
  232         reference_frame=pin.ReferenceFrame.LOCAL,
 
  234         if update_kinematics:
 
  244         update_kinematics=True,
 
  245         reference_frame=pin.ReferenceFrame.LOCAL,
 
  247         if update_kinematics:
 
  250             self.
model, self.
data, index, reference_frame
 
  272                 self.
model, self.
data, geom_model, geom_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:
 
  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. 
  323         Similar to getFrameJacobian but does not need pin.computeJointJacobians and 
  324         pin.updateFramePlacements to update internal value of self.data related to 
  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"]
 
  
def __init__(self, model=pin.Model(), collision_model=None, visual_model=None, verbose=False)
def play(self, q_trajectory, dt)
def BuildFromSDF(filename, *args, **kwargs)
void updateGeometryPlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data)
Update the placement of the geometry objects according to the current joint placements contained in d...
def computeJointJacobian(self, q, index)
MotionTpl< Scalar, Options > getFrameClassicalAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
Returns the "classical" acceleration of the Frame expressed in the desired reference frame....
def frameVelocity(self, q, v, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
def initViewer(self, share_data=True, *args, **kwargs)
def centroidalMomentumVariation(self, q, v, a)
tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] buildModelsFromUrdf(filename, *args, **kwargs)
JointIndex id(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdVisitor to get the index of the joint in the kinematic chain.
def velocity(self, q, v, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
def getViewerNodeName(self, geometry_object, geometry_type)
def computeJointJacobians(self, q)
def placement(self, q, index, update_kinematics=True)
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame)
Computes the Jacobian of a specific joint frame expressed either in the world (rf = WORLD) frame,...
MotionTpl< Scalar, Options > getFrameAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
Returns the spatial acceleration of the Frame expressed in the desired reference frame....
def setVisualizer(self, visualizer, init=True, copy_models=False)
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Convention convention=Convention::LOCAL)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
def buildReducedRobot(self, list_of_joints_to_lock, reference_configuration=None)
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
Update the joint placements, spatial velocities and spatial accelerations according to the current jo...
def acceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
def frameAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
def loadViewerModel(self, *args, **kwargs)
def getJointJacobian(self, index, rf_frame=pin.ReferenceFrame.LOCAL)
tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] buildModelsFromSdf(filename, *args, **kwargs)
MotionTpl< Scalar, Options > getFrameVelocity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
Returns the spatial velocity of the Frame expressed in the desired reference frame....
def com(self, q=None, v=None, a=None)
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeCentroidalMap(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the Centroidal Momentum Matrix.
def BuildFromMJCF(filename, *args, **kwargs)
def displayCollisions(self, visibility)
def classicalAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
def framePlacement(self, q, index, update_kinematics=True)
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & ccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Centroidal Momentum Matrix, the Composite Ridig Body Inertia as well as the centroidal m...
def BuildFromURDF(filename, *args, **kwargs)
def getFrameJacobian(self, frame_id, rf_frame=pin.ReferenceFrame.LOCAL)
def centroidalMomentum(self, q, v)
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & nonLinearEffects(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the non-linear effects (Corriolis, centrifual and gravitationnal effects),...
void computeFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frame_id, const Eigen::MatrixBase< Matrix6xLike > &J)
Computes the Jacobian of a specific Frame expressed in the LOCAL frame coordinate system.
void framesForwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
First calls the forwardKinematics on the model, then computes the placement of each frame....
Eigen::Matrix< typename LieGroupCollection::Scalar, Eigen::Dynamic, 1, LieGroupCollection::Options > neutral(const LieGroupGenericTpl< LieGroupCollection > &lg)
Visit a LieGroupVariant to get the neutral element of it.
MotionTpl< Scalar, Options > getVelocity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
Returns the spatial velocity of the joint expressed in the desired reference frame....
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & centerOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
Computes the center of mass position, velocity and acceleration of a given model according to the cur...
def computeFrameJacobian(self, q, frame_id)
def initFromMJCF(self, filename, *args, **kwargs)
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the world frame....
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & jacobianCenterOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
Computes both the jacobian and the the center of mass position of a given model according to the curr...
def initFromSDF(self, filename, *args, **kwargs)
def initFromURDF(self, filename, *args, **kwargs)
def displayVisuals(self, visibility)
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > getFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame reference_frame)
Returns the jacobian of the frame expressed either expressed in the local frame coordinate system,...
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalMomentumTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and...
def centroidal(self, q, v)
void computeJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex joint_id, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store t...
MotionTpl< Scalar, Options > getClassicalAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
Returns the "classical" acceleration of the joint expressed in the desired reference frame....
def framesForwardKinematics(self, q)
def forwardKinematics(self, q, v=None, a=None)
def frameClassicalAcceleration(self, q, v, a, index, update_kinematics=True, reference_frame=pin.ReferenceFrame.LOCAL)
const DataTpl< Scalar, Options, JointCollectionTpl >::SE3 & updateFramePlacement(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id)
Updates the placement of the given frame.
void buildReducedModel(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::vector< GeometryModel, GeometryModelAllocator > &list_of_geom_models, const std::vector< JointIndex > &list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration, ModelTpl< Scalar, Options, JointCollectionTpl > &reduced_model, std::vector< GeometryModel, GeometryModelAllocator > &list_of_reduced_geom_models)
Build a reduced model and a rededuced geometry model from a given input model, a given input geometry...
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalMomentum(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Centroidal momentum, a.k.a. the total momenta of the system expressed around the center ...
MotionTpl< Scalar, Options > getAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
Returns the spatial acceleration of the joint expressed in the desired reference frame....
def updateGeometryPlacements(self, q=None, visual=False)
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & computeGeneralizedGravity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the generalized gravity contribution  of the Lagrangian dynamics:
def centroidalMap(self, q)
def buildModelsFromMJCF(filename, *args, **kwargs)
pinocchio
Author(s): 
autogenerated on Wed May 28 2025 02:41:21