|
def | __init__ (self, urdf, pkgs) |
|
def | display (self, q) |
|
def | initDisplay (self, loadModel) |
|
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 | 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) |
|
The class models a mobile robot with UR5 arm, feature 3+6 DOF.
The configuration of the basis is represented by [X, Y, cos, sin], with the
additionnal constraint that (cos, sin) should have norm 1. Hence take care when
sampling and integrating configurations.
The robot is depicted as an orange box with two black cylinders (wheels) atop of
which is the classical (realistic) UR5 model.
The model also features to OPERATIONAL frames, named "mobile" (on the front of the
mobile basis, 30cm above the ground) and "tool" (at the very end of the effector).
Definition at line 7 of file mobilerobot.py.