Welcome to Orocos KDL python bindings’s documentation!¶
Overview of all available classes and functions for the Orocos KDL python bindings. This documentation is autogenerated and only shows the API of all functions. Please refer to http://www.orocos.org/kdl/user-manual or to the C++ API documentation at http://docs.ros.org/api/orocos_kdl/html/ for more documentation.
Indices and tables¶
Orocos KDL Python wrapper
- PyKDL.Add(*args, **kwargs)¶
Overloaded function.
Add(src1: PyKDL.JntArray, src2: PyKDL.JntArray, dest: PyKDL.JntArray) -> None
Add(src1: PyKDL.JntArrayVel, src2: PyKDL.JntArrayVel, dest: PyKDL.JntArrayVel) -> None
Add(src1: PyKDL.JntArrayVel, src2: PyKDL.JntArray, dest: PyKDL.JntArrayVel) -> None
Add(src1: PyKDL.JntSpaceInertiaMatrix, src2: PyKDL.JntSpaceInertiaMatrix, dest: PyKDL.JntSpaceInertiaMatrix) -> None
- class PyKDL.Chain¶
- addChain(self: PyKDL.Chain, chain: PyKDL.Chain) None ¶
- addSegment(self: PyKDL.Chain, segment: PyKDL.Segment) None ¶
- getNrOfJoints(self: PyKDL.Chain) int ¶
- getNrOfSegments(self: PyKDL.Chain) int ¶
- getSegment(*args, **kwargs)¶
Overloaded function.
getSegment(self: PyKDL.Chain, index: int) -> PyKDL.Segment
getSegment(self: PyKDL.Chain, index: int) -> PyKDL.Segment
- class PyKDL.ChainDynParam¶
- JntToCoriolis(self: PyKDL.ChainDynParam, q: PyKDL.JntArray, q_dot: PyKDL.JntArray, coriolis: PyKDL.JntArray) int ¶
- JntToGravity(self: PyKDL.ChainDynParam, q: PyKDL.JntArray, gravity: PyKDL.JntArray) int ¶
- JntToMass(self: PyKDL.ChainDynParam, q: PyKDL.JntArray, H: PyKDL.JntSpaceInertiaMatrix) int ¶
- class PyKDL.ChainFkSolverPos¶
- JntToCart(self: PyKDL.ChainFkSolverPos, q_in: PyKDL.JntArray, p_out: PyKDL.Frame, segmentNr: int = -1) int ¶
- class PyKDL.ChainFkSolverPos_recursive¶
- class PyKDL.ChainFkSolverVel¶
- JntToCart(self: PyKDL.ChainFkSolverVel, q_in: PyKDL.JntArrayVel, p_out: PyKDL.FrameVel, segmentNr: int = -1) int ¶
- class PyKDL.ChainFkSolverVel_recursive¶
- class PyKDL.ChainIdSolver¶
- CartToJnt(self: PyKDL.ChainIdSolver, q: PyKDL.JntArray, q_dot: PyKDL.JntArray, q_dot_dot: PyKDL.JntArray, f_ext: list[PyKDL.Wrench], torques: PyKDL.JntArray) int ¶
- class PyKDL.ChainIdSolver_RNE¶
- class PyKDL.ChainIkSolverPos¶
- CartToJnt(self: PyKDL.ChainIkSolverPos, q_init: PyKDL.JntArray, p_in: PyKDL.Frame, q_out: PyKDL.JntArray) int ¶
- class PyKDL.ChainIkSolverPos_LMA¶
- class PyKDL.ChainIkSolverPos_NR¶
- class PyKDL.ChainIkSolverPos_NR_JL¶
- class PyKDL.ChainIkSolverVel¶
- CartToJnt(self: PyKDL.ChainIkSolverVel, q_in: PyKDL.JntArray, v_in: PyKDL.Twist, q_dot_out: PyKDL.JntArray) int ¶
- class PyKDL.ChainIkSolverVel_pinv¶
- class PyKDL.ChainIkSolverVel_pinv_givens¶
- class PyKDL.ChainIkSolverVel_pinv_nso¶
- getAlpha(self: PyKDL.ChainIkSolverVel_pinv_nso) float ¶
- getOptPos(self: PyKDL.ChainIkSolverVel_pinv_nso) PyKDL.JntArray ¶
- getWeights(self: PyKDL.ChainIkSolverVel_pinv_nso) PyKDL.JntArray ¶
- setAlpha(self: PyKDL.ChainIkSolverVel_pinv_nso, alpha: float) int ¶
- setOptPos(self: PyKDL.ChainIkSolverVel_pinv_nso, opt_pos: PyKDL.JntArray) int ¶
- setWeights(self: PyKDL.ChainIkSolverVel_pinv_nso, weights: PyKDL.JntArray) int ¶
- class PyKDL.ChainIkSolverVel_wdls¶
- getEps(self: PyKDL.ChainIkSolverVel_wdls) float ¶
- getLambda(self: PyKDL.ChainIkSolverVel_wdls) float ¶
- getLambdaScaled(self: PyKDL.ChainIkSolverVel_wdls) float ¶
- getNrZeroSigmas(self: PyKDL.ChainIkSolverVel_wdls) int ¶
- getSVDResult(self: PyKDL.ChainIkSolverVel_wdls) int ¶
- getSigma(self: PyKDL.ChainIkSolverVel_wdls, sigma_out: numpy.ndarray[numpy.float64[m, 1]]) int ¶
- getSigmaMin(self: PyKDL.ChainIkSolverVel_wdls) float ¶
- setEps(self: PyKDL.ChainIkSolverVel_wdls, eps: float) None ¶
- setLambda(self: PyKDL.ChainIkSolverVel_wdls, lambda: float) None ¶
- setMaxIter(self: PyKDL.ChainIkSolverVel_wdls, max_iter: int) None ¶
- setWeightJS(self: PyKDL.ChainIkSolverVel_wdls, matrix: numpy.ndarray[numpy.float64[m, n]]) int ¶
- setWeightTS(self: PyKDL.ChainIkSolverVel_wdls, matrix: numpy.ndarray[numpy.float64[m, n]]) int ¶
- class PyKDL.ChainJntToJacDotSolver¶
- BODYFIXED = 1¶
- E_FKSOLVERPOS_FAILED = -102¶
- E_JACSOLVER_FAILED = -101¶
- E_JAC_DOT_FAILED = -100¶
- HYBRID = 0¶
- INERTIAL = 2¶
- JntToJacDot(*args, **kwargs)¶
Overloaded function.
JntToJacDot(self: PyKDL.ChainJntToJacDotSolver, q_in: PyKDL.JntArrayVel, jdot: PyKDL.Jacobian, seg_nr: int = -1) -> int
JntToJacDot(self: PyKDL.ChainJntToJacDotSolver, q_in: PyKDL.JntArrayVel, jac_dot_q_dot: PyKDL.Twist, seg_nr: int = -1) -> int
- setBodyFixedRepresentation(self: PyKDL.ChainJntToJacDotSolver) None ¶
- setHybridRepresentation(self: PyKDL.ChainJntToJacDotSolver) None ¶
- setInertialRepresentation(self: PyKDL.ChainJntToJacDotSolver) None ¶
- setLockedJoints(self: PyKDL.ChainJntToJacDotSolver, locked_joints: list[bool]) int ¶
- setRepresentation(self: PyKDL.ChainJntToJacDotSolver, representation: int) None ¶
- class PyKDL.ChainJntToJacSolver¶
- JntToJac(self: PyKDL.ChainJntToJacSolver, q_in: PyKDL.JntArray, jac: PyKDL.Jacobian, seg_nr: int = -1) int ¶
- setLockedJoints(self: PyKDL.ChainJntToJacSolver, locked_joints: list[bool]) int ¶
- PyKDL.Divide(*args, **kwargs)¶
Overloaded function.
Divide(src: PyKDL.JntArray, factor: float, dest: PyKDL.JntArray) -> None
Divide(src: PyKDL.JntArrayVel, factor: float, dest: PyKDL.JntArrayVel) -> None
Divide(src: PyKDL.JntArrayVel, factor: PyKDL.doubleVel, dest: PyKDL.JntArrayVel) -> None
Divide(src: PyKDL.JntSpaceInertiaMatrix, factor: float, dest: PyKDL.JntSpaceInertiaMatrix) -> None
- PyKDL.Equal(*args, **kwargs)¶
Overloaded function.
Equal(a: PyKDL.Vector, b: PyKDL.Vector, eps: float = 1e-06) -> bool
Equal(a: PyKDL.Wrench, b: PyKDL.Wrench, eps: float = 1e-06) -> bool
Equal(a: PyKDL.Twist, b: PyKDL.Twist, eps: float = 1e-06) -> bool
Equal(a: PyKDL.Rotation, b: PyKDL.Rotation, eps: float = 1e-06) -> bool
Equal(a: PyKDL.Frame, b: PyKDL.Frame, eps: float = 1e-06) -> bool
Equal(r1: PyKDL.doubleVel, r2: PyKDL.doubleVel, eps: float = 1e-06) -> bool
Equal(r1: PyKDL.VectorVel, r2: PyKDL.VectorVel, eps: float = 1e-06) -> bool
Equal(r1: PyKDL.Vector, r2: PyKDL.VectorVel, eps: float = 1e-06) -> bool
Equal(r1: PyKDL.VectorVel, r2: PyKDL.Vector, eps: float = 1e-06) -> bool
Equal(a: PyKDL.TwistVel, b: PyKDL.TwistVel, eps: float = 1e-06) -> bool
Equal(a: PyKDL.Twist, b: PyKDL.TwistVel, eps: float = 1e-06) -> bool
Equal(a: PyKDL.TwistVel, b: PyKDL.Twist, eps: float = 1e-06) -> bool
Equal(r1: PyKDL.RotationVel, r2: PyKDL.RotationVel, eps: float = 1e-06) -> bool
Equal(r1: PyKDL.Rotation, r2: PyKDL.RotationVel, eps: float = 1e-06) -> bool
Equal(r1: PyKDL.RotationVel, r2: PyKDL.Rotation, eps: float = 1e-06) -> bool
Equal(r1: PyKDL.FrameVel, r2: PyKDL.FrameVel, eps: float = 1e-06) -> bool
Equal(r1: PyKDL.Frame, r2: PyKDL.FrameVel, eps: float = 1e-06) -> bool
Equal(r1: PyKDL.FrameVel, r2: PyKDL.Frame, eps: float = 1e-06) -> bool
Equal(src1: PyKDL.JntArray, src2: PyKDL.JntArray, eps: float = 1e-06) -> bool
Equal(src1: PyKDL.JntArrayVel, src2: PyKDL.JntArrayVel, eps: float = 1e-06) -> bool
Equal(src1: PyKDL.JntSpaceInertiaMatrix, src2: PyKDL.JntSpaceInertiaMatrix, eps: float = 1e-06) -> bool
- class PyKDL.Frame¶
- static DH(a: float, alpha: float, d: float, theta: float) PyKDL.Frame ¶
- static DH_Craig1989(a: float, alpha: float, d: float, theta: float) PyKDL.Frame ¶
- static Identity() PyKDL.Frame ¶
- Integrate(self: PyKDL.Frame, twist: PyKDL.Twist, sample_frequency: float) None ¶
- Inverse(*args, **kwargs)¶
Overloaded function.
Inverse(self: PyKDL.Frame) -> PyKDL.Frame
Inverse(self: PyKDL.Frame, arg0: PyKDL.Vector) -> PyKDL.Vector
Inverse(self: PyKDL.Frame, arg0: PyKDL.Wrench) -> PyKDL.Wrench
Inverse(self: PyKDL.Frame, arg0: PyKDL.Twist) -> PyKDL.Twist
- property M¶
- property p¶
- class PyKDL.FrameVel¶
- GetFrame(self: PyKDL.FrameVel) PyKDL.Frame ¶
- GetTwist(self: PyKDL.FrameVel) PyKDL.Twist ¶
- static Identity() PyKDL.FrameVel ¶
- Inverse(*args, **kwargs)¶
Overloaded function.
Inverse(self: PyKDL.FrameVel) -> PyKDL.FrameVel
Inverse(self: PyKDL.FrameVel, arg0: PyKDL.VectorVel) -> PyKDL.VectorVel
Inverse(self: PyKDL.FrameVel, arg0: PyKDL.Vector) -> PyKDL.VectorVel
Inverse(self: PyKDL.FrameVel, arg0: PyKDL.TwistVel) -> PyKDL.TwistVel
Inverse(self: PyKDL.FrameVel, arg0: PyKDL.Twist) -> PyKDL.TwistVel
- property M¶
- deriv(self: PyKDL.FrameVel) PyKDL.Twist ¶
- property p¶
- value(self: PyKDL.FrameVel) PyKDL.Frame ¶
- class PyKDL.Jacobian¶
- changeBase(self: PyKDL.Jacobian, rot: PyKDL.Rotation) None ¶
- changeRefFrame(self: PyKDL.Jacobian, frame: PyKDL.Frame) None ¶
- changeRefPoint(self: PyKDL.Jacobian, base: PyKDL.Vector) None ¶
- columns(self: PyKDL.Jacobian) int ¶
- getColumn(self: PyKDL.Jacobian, index: int) PyKDL.Twist ¶
- resize(self: PyKDL.Jacobian, nr_columns: int) None ¶
- rows(self: PyKDL.Jacobian) int ¶
- setColumn(self: PyKDL.Jacobian, index: int, t: PyKDL.Twist) None ¶
- class PyKDL.JntArray¶
- columns(self: PyKDL.JntArray) int ¶
- resize(self: PyKDL.JntArray, size: int) None ¶
- rows(self: PyKDL.JntArray) int ¶
- class PyKDL.JntArrayVel¶
- deriv(self: PyKDL.JntArrayVel) PyKDL.JntArray ¶
- property q¶
- property qdot¶
- resize(self: PyKDL.JntArrayVel, size: int) None ¶
- value(self: PyKDL.JntArrayVel) PyKDL.JntArray ¶
- class PyKDL.JntSpaceInertiaMatrix¶
- columns(self: PyKDL.JntSpaceInertiaMatrix) int ¶
- resize(self: PyKDL.JntSpaceInertiaMatrix, new_size: int) None ¶
- rows(self: PyKDL.JntSpaceInertiaMatrix) int ¶
- class PyKDL.Joint¶
- Fixed = <JointType.Fixed: 8>¶
- JointAxis(self: PyKDL.Joint) PyKDL.Vector ¶
- JointOrigin(self: PyKDL.Joint) PyKDL.Vector ¶
- class JointType¶
Members:
RotAxis
RotX
RotY
RotZ
TransAxis
TransX
TransY
TransZ
Fixed
- Fixed = <JointType.Fixed: 8>¶
- RotAxis = <JointType.RotAxis: 0>¶
- RotX = <JointType.RotX: 1>¶
- RotY = <JointType.RotY: 2>¶
- RotZ = <JointType.RotZ: 3>¶
- TransAxis = <JointType.TransAxis: 4>¶
- TransX = <JointType.TransX: 5>¶
- TransY = <JointType.TransY: 6>¶
- TransZ = <JointType.TransZ: 7>¶
- property name¶
- property value¶
- RotAxis = <JointType.RotAxis: 0>¶
- RotX = <JointType.RotX: 1>¶
- RotY = <JointType.RotY: 2>¶
- RotZ = <JointType.RotZ: 3>¶
- TransAxis = <JointType.TransAxis: 4>¶
- TransX = <JointType.TransX: 5>¶
- TransY = <JointType.TransY: 6>¶
- TransZ = <JointType.TransZ: 7>¶
- getName(self: PyKDL.Joint) str ¶
- getType(self: PyKDL.Joint) PyKDL.Joint.JointType ¶
- getTypeName(self: PyKDL.Joint) str ¶
- pose(self: PyKDL.Joint, q: float) PyKDL.Frame ¶
- twist(self: PyKDL.Joint, q_dot: float) PyKDL.Twist ¶
- PyKDL.Multiply(*args, **kwargs)¶
Overloaded function.
Multiply(src: PyKDL.JntArray, factor: float, dest: PyKDL.JntArray) -> None
Multiply(src: PyKDL.JntArrayVel, factor: float, dest: PyKDL.JntArrayVel) -> None
Multiply(src: PyKDL.JntArrayVel, factor: PyKDL.doubleVel, dest: PyKDL.JntArrayVel) -> None
Multiply(src: PyKDL.JntSpaceInertiaMatrix, factor: float, dest: PyKDL.JntSpaceInertiaMatrix) -> None
Multiply(src: PyKDL.JntSpaceInertiaMatrix, vec: PyKDL.JntArray, dest: PyKDL.JntArray) -> None
- PyKDL.MultiplyJacobian(jac: PyKDL.Jacobian, src: PyKDL.JntArray, dest: PyKDL.Twist) None ¶
- class PyKDL.RigidBodyInertia¶
- RefPoint(self: PyKDL.RigidBodyInertia, p: PyKDL.Vector) PyKDL.RigidBodyInertia ¶
- static Zero() PyKDL.RigidBodyInertia ¶
- getCOG(self: PyKDL.RigidBodyInertia) PyKDL.Vector ¶
- getMass(self: PyKDL.RigidBodyInertia) float ¶
- getRotationalInertia(self: PyKDL.RigidBodyInertia) PyKDL.RotationalInertia ¶
- class PyKDL.Rotation¶
- DoRotX(self: PyKDL.Rotation, angle: float) None ¶
- DoRotY(self: PyKDL.Rotation, angle: float) None ¶
- DoRotZ(self: PyKDL.Rotation, angle: float) None ¶
- static EulerZYX(alpha: float, beta: float, gamma: float) PyKDL.Rotation ¶
- static EulerZYZ(alpha: float, beta: float, gamma: float) PyKDL.Rotation ¶
- GetEulerZYX(self: PyKDL.Rotation) tuple ¶
- GetEulerZYZ(self: PyKDL.Rotation) tuple ¶
- GetQuaternion(self: PyKDL.Rotation) tuple ¶
- GetRPY(self: PyKDL.Rotation) tuple ¶
- GetRot(self: PyKDL.Rotation) PyKDL.Vector ¶
- GetRotAngle(self: PyKDL.Rotation, eps: float = 1e-06) tuple ¶
- static Identity() PyKDL.Rotation ¶
- Inverse(*args, **kwargs)¶
Overloaded function.
Inverse(self: PyKDL.Rotation) -> PyKDL.Rotation
Inverse(self: PyKDL.Rotation, arg0: PyKDL.Vector) -> PyKDL.Vector
Inverse(self: PyKDL.Rotation, arg0: PyKDL.Wrench) -> PyKDL.Wrench
Inverse(self: PyKDL.Rotation, arg0: PyKDL.Twist) -> PyKDL.Twist
- static Quaternion(x: float, y: float, z: float, w: float) PyKDL.Rotation ¶
- static RPY(roll: float, pitch: float, yaw: float) PyKDL.Rotation ¶
- static Rot(rotvec: PyKDL.Vector, angle: float) PyKDL.Rotation ¶
- static Rot2(rotvec: PyKDL.Vector, angle: float) PyKDL.Rotation ¶
- static RotX(angle: float) PyKDL.Rotation ¶
- static RotY(angle: float) PyKDL.Rotation ¶
- static RotZ(angle: float) PyKDL.Rotation ¶
- SetInverse(self: PyKDL.Rotation) None ¶
- UnitX(*args, **kwargs)¶
Overloaded function.
UnitX(self: PyKDL.Rotation) -> PyKDL.Vector
UnitX(self: PyKDL.Rotation, vec: PyKDL.Vector) -> None
- UnitY(*args, **kwargs)¶
Overloaded function.
UnitY(self: PyKDL.Rotation) -> PyKDL.Vector
UnitY(self: PyKDL.Rotation, vec: PyKDL.Vector) -> None
- UnitZ(*args, **kwargs)¶
Overloaded function.
UnitZ(self: PyKDL.Rotation) -> PyKDL.Vector
UnitZ(self: PyKDL.Rotation, vec: PyKDL.Vector) -> None
- class PyKDL.RotationVel¶
- DoRotX(self: PyKDL.RotationVel, angle: PyKDL.doubleVel) None ¶
- DoRotY(self: PyKDL.RotationVel, angle: PyKDL.doubleVel) None ¶
- DoRotZ(self: PyKDL.RotationVel, angle: PyKDL.doubleVel) None ¶
- static Identity() PyKDL.RotationVel ¶
- Inverse(*args, **kwargs)¶
Overloaded function.
Inverse(self: PyKDL.RotationVel) -> PyKDL.RotationVel
Inverse(self: PyKDL.RotationVel, arg0: PyKDL.VectorVel) -> PyKDL.VectorVel
Inverse(self: PyKDL.RotationVel, arg0: PyKDL.Vector) -> PyKDL.VectorVel
Inverse(self: PyKDL.RotationVel, arg0: PyKDL.TwistVel) -> PyKDL.TwistVel
Inverse(self: PyKDL.RotationVel, arg0: PyKDL.Twist) -> PyKDL.TwistVel
- property R¶
- static Rot(rotvec: PyKDL.Vector, angle: PyKDL.doubleVel) PyKDL.RotationVel ¶
- static Rot2(rotvec: PyKDL.Vector, angle: PyKDL.doubleVel) PyKDL.RotationVel ¶
- static RotX(angle: PyKDL.doubleVel) PyKDL.RotationVel ¶
- static RotY(angle: PyKDL.doubleVel) PyKDL.RotationVel ¶
- static RotZ(angle: PyKDL.doubleVel) PyKDL.RotationVel ¶
- UnitX(self: PyKDL.RotationVel) PyKDL.VectorVel ¶
- UnitY(self: PyKDL.RotationVel) PyKDL.VectorVel ¶
- UnitZ(self: PyKDL.RotationVel) PyKDL.VectorVel ¶
- deriv(self: PyKDL.RotationVel) PyKDL.Vector ¶
- value(self: PyKDL.RotationVel) PyKDL.Rotation ¶
- property w¶
- class PyKDL.RotationalInertia¶
- static Zero() PyKDL.RotationalInertia ¶
- class PyKDL.Segment¶
- getFrameToTip(self: PyKDL.Segment) PyKDL.Frame ¶
- getInertia(self: PyKDL.Segment) PyKDL.RigidBodyInertia ¶
- getJoint(self: PyKDL.Segment) PyKDL.Joint ¶
- getName(self: PyKDL.Segment) str ¶
- pose(self: PyKDL.Segment, q: float) PyKDL.Frame ¶
- setInertia(self: PyKDL.Segment, I_in: PyKDL.RigidBodyInertia) None ¶
- twist(self: PyKDL.Segment, q: float, q_dot: float) PyKDL.Twist ¶
- PyKDL.SetToZero(*args, **kwargs)¶
Overloaded function.
SetToZero(vector: PyKDL.Vector) -> None
SetToZero(wrench: PyKDL.Wrench) -> None
SetToZero(twist: PyKDL.Twist) -> None
SetToZero(vector_vel: PyKDL.VectorVel) -> None
SetToZero(twist_vel: PyKDL.TwistVel) -> None
SetToZero(jac: PyKDL.Jacobian) -> None
SetToZero(jnt_array: PyKDL.JntArray) -> None
SetToZero(jnt_array_vel: PyKDL.JntArrayVel) -> None
SetToZero(matrix: PyKDL.JntSpaceInertiaMatrix) -> None
- class PyKDL.SolverI¶
- getError(self: PyKDL.SolverI) int ¶
- strError(self: PyKDL.SolverI, error: int) str ¶
- updateInternalDataStructures(self: PyKDL.SolverI) None ¶
- PyKDL.Subtract(*args, **kwargs)¶
Overloaded function.
Subtract(src1: PyKDL.JntArray, src2: PyKDL.JntArray, dest: PyKDL.JntArray) -> None
Subtract(src1: PyKDL.JntArrayVel, src2: PyKDL.JntArrayVel, dest: PyKDL.JntArrayVel) -> None
Subtract(src1: PyKDL.JntArrayVel, src2: PyKDL.JntArray, dest: PyKDL.JntArrayVel) -> None
Subtract(src1: PyKDL.JntSpaceInertiaMatrix, src2: PyKDL.JntSpaceInertiaMatrix, dest: PyKDL.JntSpaceInertiaMatrix) -> None
- class PyKDL.Tree¶
- addChain(self: PyKDL.Tree, chain: PyKDL.Chain, hook_name: str) bool ¶
- addSegment(self: PyKDL.Tree, segment: PyKDL.Segment, hook_name: str) bool ¶
- addTree(self: PyKDL.Tree, tree: PyKDL.Tree, hook_name: str) bool ¶
- getChain(self: PyKDL.Tree, chain_root: str, chain_tip: str) PyKDL.Chain ¶
- getNrOfJoints(self: PyKDL.Tree) int ¶
- getNrOfSegments(self: PyKDL.Tree) int ¶
- class PyKDL.Twist¶
- RefPoint(self: PyKDL.Twist, base: PyKDL.Vector) PyKDL.Twist ¶
- ReverseSign(self: PyKDL.Twist) None ¶
- static Zero() PyKDL.Twist ¶
- property rot¶
- property vel¶
- class PyKDL.TwistVel¶
- GetTwist(self: PyKDL.TwistVel) PyKDL.Twist ¶
- GetTwistDot(self: PyKDL.TwistVel) PyKDL.Twist ¶
- RefPoint(self: PyKDL.TwistVel, base: PyKDL.VectorVel) PyKDL.TwistVel ¶
- ReverseSign(self: PyKDL.TwistVel) None ¶
- static Zero() PyKDL.TwistVel ¶
- deriv(self: PyKDL.TwistVel) PyKDL.Twist ¶
- property rot¶
- value(self: PyKDL.TwistVel) PyKDL.Twist ¶
- property vel¶
- class PyKDL.Vector¶
- Norm(self: PyKDL.Vector, eps: float = 1e-06) float ¶
- Normalize(self: PyKDL.Vector, eps: float = 1e-06) float ¶
- ReverseSign(self: PyKDL.Vector) None ¶
- static Zero() PyKDL.Vector ¶
- x(*args, **kwargs)¶
Overloaded function.
x(self: PyKDL.Vector, value: float) -> None
x(self: PyKDL.Vector) -> float
- y(*args, **kwargs)¶
Overloaded function.
y(self: PyKDL.Vector, value: float) -> None
y(self: PyKDL.Vector) -> float
- z(*args, **kwargs)¶
Overloaded function.
z(self: PyKDL.Vector, value: float) -> None
z(self: PyKDL.Vector) -> float
- class PyKDL.VectorVel¶
- Norm(self: PyKDL.VectorVel, eps: float = 1e-06) PyKDL.doubleVel ¶
- ReverseSign(self: PyKDL.VectorVel) None ¶
- static Zero() PyKDL.VectorVel ¶
- deriv(self: PyKDL.VectorVel) PyKDL.Vector ¶
- property p¶
- property v¶
- value(self: PyKDL.VectorVel) PyKDL.Vector ¶
- class PyKDL.Wrench¶
- RefPoint(self: PyKDL.Wrench, base: PyKDL.Vector) PyKDL.Wrench ¶
- ReverseSign(self: PyKDL.Wrench) None ¶
- static Zero() PyKDL.Wrench ¶
- property force¶
- property torque¶
- PyKDL.addDelta(*args, **kwargs)¶
Overloaded function.
addDelta(a: PyKDL.Vector, da: PyKDL.Vector, dt: float = 1) -> PyKDL.Vector
addDelta(a: PyKDL.Rotation, da: PyKDL.Vector, dt: float = 1) -> PyKDL.Rotation
addDelta(a: PyKDL.Frame, da: PyKDL.Twist, dt: float = 1) -> PyKDL.Frame
addDelta(a: PyKDL.Twist, da: PyKDL.Twist, dt: float = 1) -> PyKDL.Twist
addDelta(a: PyKDL.Wrench, da: PyKDL.Wrench, dt: float = 1) -> PyKDL.Wrench
addDelta(a: PyKDL.doubleVel, da: PyKDL.doubleVel, dt: float = 1.0) -> PyKDL.doubleVel
addDelta(a: PyKDL.VectorVel, da: PyKDL.VectorVel, dt: float = 1.0) -> PyKDL.VectorVel
addDelta(a: PyKDL.RotationVel, da: PyKDL.VectorVel, dt: float = 1.0) -> PyKDL.RotationVel
addDelta(a: PyKDL.FrameVel, da: PyKDL.TwistVel, dt: float = 1.0) -> PyKDL.FrameVel
- PyKDL.changeBase(src: PyKDL.Jacobian, rot: PyKDL.Rotation, dest: PyKDL.Jacobian) bool ¶
- PyKDL.changeRefFrame(src: PyKDL.Jacobian, frame: PyKDL.Frame, dest: PyKDL.Jacobian) bool ¶
- PyKDL.changeRefPoint(src: PyKDL.Jacobian, base: PyKDL.Vector, dest: PyKDL.Jacobian) bool ¶
- PyKDL.diff(*args, **kwargs)¶
Overloaded function.
diff(a: PyKDL.Vector, b: PyKDL.Vector, dt: float = 1) -> PyKDL.Vector
diff(a: PyKDL.Rotation, b: PyKDL.Rotation, dt: float = 1) -> PyKDL.Vector
diff(a: PyKDL.Frame, b: PyKDL.Frame, dt: float = 1) -> PyKDL.Twist
diff(a: PyKDL.Twist, b: PyKDL.Twist, dt: float = 1) -> PyKDL.Twist
diff(a: PyKDL.Wrench, b: PyKDL.Wrench, dt: float = 1) -> PyKDL.Wrench
diff(a: PyKDL.doubleVel, b: PyKDL.doubleVel, dt: float = 1.0) -> PyKDL.doubleVel
diff(a: PyKDL.VectorVel, b: PyKDL.VectorVel, dt: float = 1.0) -> PyKDL.VectorVel
diff(a: PyKDL.RotationVel, b: PyKDL.RotationVel, dt: float = 1.0) -> PyKDL.VectorVel
diff(a: PyKDL.FrameVel, b: PyKDL.FrameVel, dt: float = 1.0) -> PyKDL.TwistVel
- PyKDL.dot(*args, **kwargs)¶
Overloaded function.
dot(arg0: PyKDL.Vector, arg1: PyKDL.Vector) -> float
dot(arg0: PyKDL.Twist, arg1: PyKDL.Wrench) -> float
dot(arg0: PyKDL.Wrench, arg1: PyKDL.Twist) -> float
dot(arg0: PyKDL.VectorVel, arg1: PyKDL.VectorVel) -> PyKDL.doubleVel
dot(arg0: PyKDL.VectorVel, arg1: PyKDL.Vector) -> PyKDL.doubleVel
dot(arg0: PyKDL.Vector, arg1: PyKDL.VectorVel) -> PyKDL.doubleVel
- class PyKDL.doubleVel¶
- deriv(self: PyKDL.doubleVel) float ¶
- property grad¶
- property t¶
- value(self: PyKDL.doubleVel) float ¶