Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
pinocchio.robot_wrapper.RobotWrapper Class Reference
Inheritance diagram for pinocchio.robot_wrapper.RobotWrapper:
Inheritance graph
[legend]

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 initFromSDF (self, filename, package_dirs=None, root_joint=None, root_link_name="", parent_guidance=[], verbose=False, meshLoader=None)
 
def initFromURDF (self, filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None)
 
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 BuildFromSDF (filename, package_dirs=None, root_joint=None, root_link_name="", parent_guidance=[], verbose=False, meshLoader=None)
 
def BuildFromURDF (filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None)
 

Public Attributes

 collision_data
 
 collision_model
 
 constraint_models
 
 data
 
 model
 
 q0
 
 v0
 
 visual_data
 
 visual_model
 
 viz
 

Detailed Description

Definition at line 12 of file robot_wrapper.py.

Constructor & Destructor Documentation

◆ __init__()

def pinocchio.robot_wrapper.RobotWrapper.__init__ (   self,
  model = pin.Model(),
  collision_model = None,
  visual_model = None,
  verbose = False 
)

Definition at line 88 of file robot_wrapper.py.

Member Function Documentation

◆ acceleration()

def pinocchio.robot_wrapper.RobotWrapper.acceleration (   self,
  q,
  v,
  a,
  index,
  update_kinematics = True,
  reference_frame = pin.ReferenceFrame.LOCAL 
)

Definition at line 191 of file robot_wrapper.py.

◆ acom()

def pinocchio.robot_wrapper.RobotWrapper.acom (   self,
  q,
  v,
  a 
)

Definition at line 128 of file robot_wrapper.py.

◆ BuildFromSDF()

def pinocchio.robot_wrapper.RobotWrapper.BuildFromSDF (   filename,
  package_dirs = None,
  root_joint = None,
  root_link_name = "",
  parent_guidance = [],
  verbose = False,
  meshLoader = None 
)
static

Definition at line 40 of file robot_wrapper.py.

◆ BuildFromURDF()

def pinocchio.robot_wrapper.RobotWrapper.BuildFromURDF (   filename,
  package_dirs = None,
  root_joint = None,
  verbose = False,
  meshLoader = None 
)
static

Definition at line 14 of file robot_wrapper.py.

◆ buildReducedRobot()

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 291 of file robot_wrapper.py.

◆ centroidal()

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 141 of file robot_wrapper.py.

◆ centroidalMap()

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 135 of file robot_wrapper.py.

◆ centroidalMomentum()

def pinocchio.robot_wrapper.RobotWrapper.centroidalMomentum (   self,
  q,
  v 
)

Definition at line 132 of file robot_wrapper.py.

◆ centroidalMomentumVariation()

def pinocchio.robot_wrapper.RobotWrapper.centroidalMomentumVariation (   self,
  q,
  v,
  a 
)

Definition at line 148 of file robot_wrapper.py.

◆ classicalAcceleration()

def pinocchio.robot_wrapper.RobotWrapper.classicalAcceleration (   self,
  q,
  v,
  a,
  index,
  update_kinematics = True,
  reference_frame = pin.ReferenceFrame.LOCAL 
)

Definition at line 204 of file robot_wrapper.py.

◆ com()

def pinocchio.robot_wrapper.RobotWrapper.com (   self,
  q = None,
  v = None,
  a = None 
)

Definition at line 112 of file robot_wrapper.py.

◆ computeFrameJacobian()

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 332 of file robot_wrapper.py.

◆ computeJointJacobian()

def pinocchio.robot_wrapper.RobotWrapper.computeJointJacobian (   self,
  q,
  index 
)

Definition at line 264 of file robot_wrapper.py.

◆ computeJointJacobians()

def pinocchio.robot_wrapper.RobotWrapper.computeJointJacobians (   self,
  q 
)

Definition at line 270 of file robot_wrapper.py.

◆ display()

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 413 of file robot_wrapper.py.

◆ displayCollisions()

def pinocchio.robot_wrapper.RobotWrapper.displayCollisions (   self,
  visibility 
)
Set whether to diplay collision objects or not

Definition at line 417 of file robot_wrapper.py.

◆ displayVisuals()

def pinocchio.robot_wrapper.RobotWrapper.displayVisuals (   self,
  visibility 
)
Set whether to diplay visual objects or not

Definition at line 421 of file robot_wrapper.py.

◆ forwardKinematics()

def pinocchio.robot_wrapper.RobotWrapper.forwardKinematics (   self,
  q,
  v = None,
  a = None 
)

Definition at line 165 of file robot_wrapper.py.

◆ frameAcceleration()

def pinocchio.robot_wrapper.RobotWrapper.frameAcceleration (   self,
  q,
  v,
  a,
  index,
  update_kinematics = True,
  reference_frame = pin.ReferenceFrame.LOCAL 
)

Definition at line 236 of file robot_wrapper.py.

◆ frameClassicalAcceleration()

def pinocchio.robot_wrapper.RobotWrapper.frameClassicalAcceleration (   self,
  q,
  v,
  a,
  index,
  update_kinematics = True,
  reference_frame = pin.ReferenceFrame.LOCAL 
)

Definition at line 249 of file robot_wrapper.py.

◆ framePlacement()

def pinocchio.robot_wrapper.RobotWrapper.framePlacement (   self,
  q,
  index,
  update_kinematics = True 
)

Definition at line 219 of file robot_wrapper.py.

◆ framesForwardKinematics()

def pinocchio.robot_wrapper.RobotWrapper.framesForwardKinematics (   self,
  q 
)

Definition at line 288 of file robot_wrapper.py.

◆ frameVelocity()

def pinocchio.robot_wrapper.RobotWrapper.frameVelocity (   self,
  q,
  v,
  index,
  update_kinematics = True,
  reference_frame = pin.ReferenceFrame.LOCAL 
)

Definition at line 224 of file robot_wrapper.py.

◆ getFrameJacobian()

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 325 of file robot_wrapper.py.

◆ getJointJacobian()

def pinocchio.robot_wrapper.RobotWrapper.getJointJacobian (   self,
  index,
  rf_frame = pin.ReferenceFrame.LOCAL 
)

Definition at line 267 of file robot_wrapper.py.

◆ getViewerNodeName()

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 382 of file robot_wrapper.py.

◆ gravity()

def pinocchio.robot_wrapper.RobotWrapper.gravity (   self,
  q 
)

Definition at line 162 of file robot_wrapper.py.

◆ index()

def pinocchio.robot_wrapper.RobotWrapper.index (   self,
  name 
)

Definition at line 362 of file robot_wrapper.py.

◆ initFromSDF()

def pinocchio.robot_wrapper.RobotWrapper.initFromSDF (   self,
  filename,
  package_dirs = None,
  root_joint = None,
  root_link_name = "",
  parent_guidance = [],
  verbose = False,
  meshLoader = None 
)

Definition at line 61 of file robot_wrapper.py.

◆ initFromURDF()

def pinocchio.robot_wrapper.RobotWrapper.initFromURDF (   self,
  filename,
  package_dirs = None,
  root_joint = None,
  verbose = False,
  meshLoader = None 
)

Definition at line 21 of file robot_wrapper.py.

◆ initViewer()

def pinocchio.robot_wrapper.RobotWrapper.initViewer (   self,
  share_data = True,
args,
**  kwargs 
)
Init the viewer

Definition at line 386 of file robot_wrapper.py.

◆ Jcom()

def pinocchio.robot_wrapper.RobotWrapper.Jcom (   self,
  q 
)

Definition at line 153 of file robot_wrapper.py.

◆ loadViewerModel()

def pinocchio.robot_wrapper.RobotWrapper.loadViewerModel (   self,
args,
**  kwargs 
)
Create the scene displaying the robot meshes in gepetto-viewer

Definition at line 409 of file robot_wrapper.py.

◆ mass()

def pinocchio.robot_wrapper.RobotWrapper.mass (   self,
  q 
)

Definition at line 156 of file robot_wrapper.py.

◆ nle()

def pinocchio.robot_wrapper.RobotWrapper.nle (   self,
  q,
  v 
)

Definition at line 159 of file robot_wrapper.py.

◆ nq()

def pinocchio.robot_wrapper.RobotWrapper.nq (   self)

Definition at line 105 of file robot_wrapper.py.

◆ nv()

def pinocchio.robot_wrapper.RobotWrapper.nv (   self)

Definition at line 109 of file robot_wrapper.py.

◆ placement()

def pinocchio.robot_wrapper.RobotWrapper.placement (   self,
  q,
  index,
  update_kinematics = True 
)

Definition at line 174 of file robot_wrapper.py.

◆ play()

def pinocchio.robot_wrapper.RobotWrapper.play (   self,
  q_trajectory,
  dt 
)
Play a trajectory with given time step

Definition at line 425 of file robot_wrapper.py.

◆ rebuildData()

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 339 of file robot_wrapper.py.

◆ setVisualizer()

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 372 of file robot_wrapper.py.

◆ updateGeometryPlacements()

def pinocchio.robot_wrapper.RobotWrapper.updateGeometryPlacements (   self,
  q = None,
  visual = False 
)

Definition at line 273 of file robot_wrapper.py.

◆ vcom()

def pinocchio.robot_wrapper.RobotWrapper.vcom (   self,
  q,
  v 
)

Definition at line 124 of file robot_wrapper.py.

◆ velocity()

def pinocchio.robot_wrapper.RobotWrapper.velocity (   self,
  q,
  v,
  index,
  update_kinematics = True,
  reference_frame = pin.ReferenceFrame.LOCAL 
)

Definition at line 179 of file robot_wrapper.py.

◆ viewer()

def pinocchio.robot_wrapper.RobotWrapper.viewer (   self)

Definition at line 369 of file robot_wrapper.py.

Member Data Documentation

◆ collision_data

pinocchio.robot_wrapper.RobotWrapper.collision_data

Definition at line 357 of file robot_wrapper.py.

◆ collision_model

pinocchio.robot_wrapper.RobotWrapper.collision_model

Definition at line 90 of file robot_wrapper.py.

◆ constraint_models

pinocchio.robot_wrapper.RobotWrapper.constraint_models

Definition at line 77 of file robot_wrapper.py.

◆ data

pinocchio.robot_wrapper.RobotWrapper.data

Definition at line 356 of file robot_wrapper.py.

◆ model

pinocchio.robot_wrapper.RobotWrapper.model

Definition at line 89 of file robot_wrapper.py.

◆ q0

pinocchio.robot_wrapper.RobotWrapper.q0

Definition at line 98 of file robot_wrapper.py.

◆ v0

pinocchio.robot_wrapper.RobotWrapper.v0

Definition at line 97 of file robot_wrapper.py.

◆ visual_data

pinocchio.robot_wrapper.RobotWrapper.visual_data

Definition at line 93 of file robot_wrapper.py.

◆ visual_model

pinocchio.robot_wrapper.RobotWrapper.visual_model

Definition at line 91 of file robot_wrapper.py.

◆ viz

pinocchio.robot_wrapper.RobotWrapper.viz

Definition at line 100 of file robot_wrapper.py.


The documentation for this class was generated from the following file:


pinocchio
Author(s):
autogenerated on Sun Jun 16 2024 02:43:17