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¶
-
PyKDL.Add(src1: JntArray, src2: JntArray, dest: JntArray)¶ Add(src1: JntArrayVel, src2: JntArrayVel, dest: JntArrayVel) Add(src1: JntArrayVel, src2: JntArray, dest: JntArrayVel) Add(src1: JntSpaceInertiaMatrix, src2: JntSpaceInertiaMatrix, dest: JntSpaceInertiaMatrix)
-
class
PyKDL.Chain¶ Chain(in_: Chain)
-
addChain(self, chain: Chain)¶
-
addSegment(self, segment: Segment)¶
-
getNrOfJoints(self) → int¶
-
getNrOfSegments(self) → int¶
-
getSegment(self, nr: int) → Segment¶
-
-
class
PyKDL.ChainDynParam(chain: Chain, _grav: Vector)¶ ChainDynParam(ChainDynParam)
-
JntToCoriolis(self, q: JntArray, q_dot: JntArray, coriolis: JntArray) → int¶
-
JntToGravity(self, q: JntArray, gravity: JntArray) → int¶
-
JntToMass(self, q: JntArray, H: JntSpaceInertiaMatrix) → int¶
-
-
class
PyKDL.ChainFkSolverPos¶
-
class
PyKDL.ChainFkSolverPos_recursive(chain: Chain)¶ ChainFkSolverPos_recursive(ChainFkSolverPos_recursive)
-
JntToCart(self, q_in: JntArray, p_out: Frame, segmentNr: int = -1) → int¶
-
updateInternalDataStructures(self)¶
-
-
class
PyKDL.ChainFkSolverVel¶
-
class
PyKDL.ChainFkSolverVel_recursive(chain: Chain)¶ ChainFkSolverVel_recursive(ChainFkSolverVel_recursive)
-
JntToCart(self, q_in: JntArrayVel, out: FrameVel, segmentNr: int = -1) → int¶
-
updateInternalDataStructures(self)¶
-
-
class
PyKDL.ChainIkSolverPos¶ ChainIkSolverPos(ChainIkSolverPos)
-
CartToJnt(self, q_init: JntArray, p_in: Frame, q_out: JntArray) → int¶
-
updateInternalDataStructures(self)¶
-
-
class
PyKDL.ChainIkSolverPos_LMA(chain: Chain, eps: float = 1e-05, _maxiter: int = 500, _eps_joints: float = 1e-15)¶ ChainIkSolverPos_LMA(ChainIkSolverPos_LMA)
-
CartToJnt(self, q_init: JntArray, p_in: Frame, q_out: JntArray) → int¶
-
updateInternalDataStructures(self)¶
-
-
class
PyKDL.ChainIkSolverPos_NR(chain: Chain, fksolver: ChainFkSolverPos, iksolver: ChainIkSolverVel, maxiter: int = 100, eps: float = epsilon)¶ ChainIkSolverPos_NR(ChainIkSolverPos_NR)
-
CartToJnt(self, q_init: JntArray, p_in: Frame, q_out: JntArray) → int¶
-
updateInternalDataStructures(self)¶
-
-
class
PyKDL.ChainIkSolverPos_NR_JL(chain: Chain, q_min: JntArray, q_max: JntArray, fksolver: ChainFkSolverPos, iksolver: ChainIkSolverVel, maxiter: int = 100, eps: float = epsilon)¶ ChainIkSolverPos_NR_JL(ChainIkSolverPos_NR_JL)
-
CartToJnt(self, q_init: JntArray, p_in: Frame, q_out: JntArray) → int¶
-
updateInternalDataStructures(self)¶
-
-
class
PyKDL.ChainIkSolverVel¶ ChainIkSolverVel(ChainIkSolverVel)
-
CartToJnt(self, q_in: JntArray, v_in: Twist, qdot_out: JntArray) → int¶ CartToJnt(self, q_init: JntArray, v_in: FrameVel, q_out: JntArrayVel) -> int
-
updateInternalDataStructures(self)¶
-
-
class
PyKDL.ChainIkSolverVel_pinv(chain: Chain, eps: float = 1e-05, maxiter: int = 150)¶ ChainIkSolverVel_pinv(ChainIkSolverVel_pinv)
-
CartToJnt(self, q_in: JntArray, v_in: Twist, qdot_out: JntArray) → int¶
-
updateInternalDataStructures(self)¶
-
-
class
PyKDL.ChainIkSolverVel_pinv_givens(chain: Chain)¶ ChainIkSolverVel_pinv_givens(ChainIkSolverVel_pinv_givens)
-
CartToJnt(self, q_in: JntArray, v_in: Twist, qdot_out: JntArray) → int¶
-
updateInternalDataStructures(self)¶
-
-
class
PyKDL.ChainIkSolverVel_pinv_nso(chain: Chain, eps: float = 1e-05, maxiter: int = 150, alpha: float = 0.25)¶ ChainIkSolverVel_pinv_nso(ChainIkSolverVel_pinv_nso)
-
CartToJnt(self, q_in: JntArray, v_in: Twist, qdot_out: JntArray) → int¶
-
getAlpha(self) → float¶
-
getOptPos(self) → JntArray¶
-
getWeights(self) → JntArray¶
-
setAlpha(self, alpha: float) → int¶
-
setOptPos(self, opt_pos: JntArray) → int¶
-
setWeights(self, weights: JntArray) → int¶
-
updateInternalDataStructures(self)¶
-
-
class
PyKDL.ChainIkSolverVel_wdls(chain: Chain, eps: float = 1e-05, maxiter: int = 150)¶ ChainIkSolverVel_wdls(ChainIkSolverVel_wdls)
-
CartToJnt(self, q_in: JntArray, v_in: Twist, qdot_out: JntArray) → int¶
-
setLambda(self, lambda_: float)¶
-
setWeightJS(self, List)¶
-
setWeightTS(self, List)¶
-
updateInternalDataStructures(self)¶
-
-
class
PyKDL.ChainJntToJacSolver(chain: Chain)¶ ChainJntToJacSolver(ChainJntToJacSolver)
-
JntToJac(self, q_in: JntArray, jac: Jacobian) → int¶
-
updateInternalDataStructures(self)¶
-
-
PyKDL.Divide(src: JntArray, factor: float, dest: JntArray)¶ Divide(src: JntArrayVel, factor: float, dest: JntArrayVel) Divide(src: JntArrayVel, factor: doubleVel, dest: JntArrayVel) Divide(src: JntSpaceInertiaMatrix, factor: float, dest: JntSpaceInertiaMatrix)
-
PyKDL.Equal(a: Vector, b: Vector, eps: float = epsilon) → bool¶ Equal(a: Rotation, b: Rotation, eps: float = epsilon) -> bool Equal(a: Frame, b: Frame, eps: float = epsilon) -> bool Equal(a: Twist, b: Twist, eps: float = epsilon) -> bool Equal(a: Wrench, b: Wrench, eps: float = epsilon) -> bool Equal(src1: JntArray, src2: JntArray, eps: float = epsilon) -> bool Equal(src1: JntArrayVel, src2: JntArrayVel, eps: float = epsilon) -> bool Equal(r1: doubleVel, r2: doubleVel, eps: float = epsilon) -> bool Equal(r1: VectorVel, r2: VectorVel, eps: float = epsilon) -> bool Equal(r1: Vector, r2: VectorVel, eps: float = epsilon) -> bool Equal(r1: VectorVel, r2: Vector, eps: float = epsilon) -> bool Equal(r1: RotationVel, r2: RotationVel, eps: float = epsilon) -> bool Equal(r1: Rotation, r2: RotationVel, eps: float = epsilon) -> bool Equal(r1: RotationVel, r2: Rotation, eps: float = epsilon) -> bool Equal(r1: FrameVel, r2: FrameVel, eps: float = epsilon) -> bool Equal(r1: Frame, r2: FrameVel, eps: float = epsilon) -> bool Equal(r1: FrameVel, r2: Frame, eps: float = epsilon) -> bool Equal(a: TwistVel, b: TwistVel, eps: float = epsilon) -> bool Equal(a: Twist, b: TwistVel, eps: float = epsilon) -> bool Equal(a: TwistVel, b: Twist, eps: float = epsilon) -> bool Equal(src1: JntSpaceInertiaMatrix, src2: JntSpaceInertiaMatrix, eps: float = epsilon) -> bool
-
class
PyKDL.Frame(R: Rotation, V: Vector)¶ Frame(V: Vector) Frame(R: Rotation) Frame() Frame(Frame)
-
DH(self, a: float, alpha: float, d: float, theta: float) → Frame¶
-
DH_Craig1989(self, a: float, alpha: float, d: float, theta: float) → Frame¶
-
Identity() → Frame¶
-
Integrate(self, t_this: Twist, frequency: float)¶
-
Inverse(self) → Frame¶ Inverse(self, arg: Vector) -> Vector Inverse(self, arg: Wrench) -> Wrench Inverse(self, arg: Twist) -> Twist
-
M¶
-
p¶
-
-
class
PyKDL.FrameVel¶ FrameVel(_T: Frame) FrameVel(_T: Frame, _t: Twist) FrameVel(_M: RotationVel, _p: VectorVel) FrameVel(FrameVel)
-
GetFrame(self) → Frame¶
-
GetTwist(self) → Twist¶
-
Identity() → FrameVel¶
-
Inverse(self) → FrameVel¶ Inverse(self, arg: VectorVel) -> VectorVel Inverse(self, arg: Vector) -> VectorVel Inverse(self, arg: TwistVel) -> TwistVel Inverse(self, arg: Twist) -> TwistVel
-
M¶
-
deriv(self) → Twist¶
-
p¶
-
value(self) → Frame¶
-
-
class
PyKDL.Jacobian(size: int)¶ Jacobian(arg: Jacobian)
-
changeBase(self, rot: Rotation)¶
-
changeRefFrame(self, frame: Frame)¶
-
changeRefPoint(self, base_AB: Vector)¶
-
columns(self) → int¶
-
getColumn(self, i: int) → Twist¶
-
resize(self, newNrOfColumns: int)¶
-
rows(self) → int¶
-
setColumn(self, i: int, t: Twist)¶
-
-
class
PyKDL.JntArray(size: int)¶ JntArray(arg: JntArray)
-
columns(self) → int¶
-
resize(self, newSize: int)¶
-
rows(self) → int¶
-
-
class
PyKDL.JntArrayVel(size: int)¶ JntArrayVel(q: JntArray, qdot: JntArray) JntArrayVel(q: JntArray) JntArrayVel(JntArrayVel)
-
deriv(self) → JntArray¶
-
q¶
-
qdot¶
-
resize(self, newSize: int)¶
-
value(self) → JntArray¶
-
-
class
PyKDL.JntSpaceInertiaMatrix¶ JntSpaceInertiaMatrix(size: int) JntSpaceInertiaMatrix(arg: JntSpaceInertiaMatrix)
-
columns(self) → int¶
-
resize(self, newSize: int)¶
-
rows(self) → int¶
-
-
class
PyKDL.Joint(name: object, type: Joint.JointType = Joint.None, scale: float = 1, offset: float = 0, inertia: float = 0, damping: float = 0, stiffness: float = 0)¶ Joint(type: Joint.JointType = Joint.None, scale: float = 1, offset: float = 0, inertia: float = 0, damping: float = 0, stiffness: float = 0) Joint(name: object, origin: Vector, axis: Vector, type: Joint.JointType, scale: float = 1, offset: float = 0, inertia: float = 0, damping: float = 0, stiffness: float = 0) Joint(origin: Vector, axis: Vector, type: Joint.JointType, scale: float = 1, offset: float = 0, inertia: float = 0, damping: float = 0, stiffness: float = 0) Joint(in_: Joint)
-
JointAxis(self) → Vector¶
-
JointOrigin(self) → Vector¶
-
class
JointType¶
-
None= 8¶
-
RotAxis= 0¶
-
RotX= 1¶
-
RotY= 2¶
-
RotZ= 3¶
-
TransAxis= 4¶
-
TransX= 5¶
-
TransY= 6¶
-
TransZ= 7¶
-
getName(self) → object¶
-
getType(self) → Joint.JointType¶
-
getTypeName(self) → object¶
-
pose(self, q: float) → Frame¶
-
twist(self, qdot: float) → Twist¶
-
-
PyKDL.Multiply(src: JntArray, factor: float, dest: JntArray)¶ Multiply(src: JntArrayVel, factor: float, dest: JntArrayVel) Multiply(src: JntArrayVel, factor: doubleVel, dest: JntArrayVel) Multiply(src: JntSpaceInertiaMatrix, factor: float, dest: JntSpaceInertiaMatrix) Multiply(src: JntSpaceInertiaMatrix, vec: JntArray, dest: JntArray)
-
PyKDL.MultiplyJacobian(jac: Jacobian, src: JntArray, dest: Twist)¶
-
class
PyKDL.RigidBodyInertia(m: float = 0, oc: Vector = Vector.Zero(), Ic: RotationalInertia = RotationalInertia.Zero())¶ RigidBodyInertia(RigidBodyInertia)
-
RefPoint(self, p: Vector) → RigidBodyInertia¶
-
Zero() → RigidBodyInertia¶
-
getCOG(self) → Vector¶
-
getMass(self) → float¶
-
getRotationalInertia(self) → RotationalInertia¶
-
-
class
PyKDL.Rotation¶ Rotation(Xx: float, Yx: float, Zx: float, Xy: float, Yy: float, Zy: float, Xz: float, Yz: float, Zz: float) Rotation(x: Vector, y: Vector, z: Vector) Rotation(Rotation)
-
DoRotX(self, angle: float)¶
-
DoRotY(self, angle: float)¶
-
DoRotZ(self, angle: float)¶
-
EulerZYX(Alfa: float, Beta: float, Gamma: float) → Rotation¶
-
EulerZYZ(Alfa: float, Beta: float, Gamma: float) → Rotation¶
-
GetEulerZYX(self) → Tuple[float, float, float]¶
-
GetEulerZYZ(self) → Tuple[float, float, float]¶
-
GetQuaternion(self) → Tuple[float, float, float, float]¶
-
GetRPY(self) → Tuple[float, float, float]¶
-
GetRot(self) → Vector¶
-
GetRotAngle(self, eps: float = epsilon) → Tuple[float, Vector]¶
-
Identity() → Rotation¶
-
Inverse(self) → Rotation¶ Inverse(self, v: Vector) -> Vector Inverse(self, w: Wrench) -> Wrench Inverse(self, t: Twist) -> Twist
-
Quaternion(x: float, y: float, z: float, w: float) → Rotation¶
-
RPY(roll: float, pitch: float, yaw: float) → Rotation¶
-
Rot(vec: Vector, angle: float) → Rotation¶
-
Rot2(vec: Vector, angle: float) → Rotation¶
-
RotX(angle: float) → Rotation¶
-
RotY(angle: float) → Rotation¶
-
RotZ(angle: float) → Rotation¶
-
SetInverse(self)¶
-
UnitX(self) → Vector¶ UnitX(self, X: Vector)
-
UnitY(self) → Vector¶ UnitY(self, X: Vector)
-
UnitZ(self) → Vector¶ UnitZ(self, X: Vector)
-
-
class
PyKDL.RotationVel¶ RotationVel(_R: Rotation) RotationVel(_R: Rotation, _w: Vector) RotationVel(RotationVel)
-
DoRotX(self, angle: doubleVel)¶
-
DoRotY(self, angle: doubleVel)¶
-
DoRotZ(self, angle: doubleVel)¶
-
Identity() → RotationVel¶
-
Inverse(self) → RotationVel¶ Inverse(self, arg: VectorVel) -> VectorVel Inverse(self, arg: Vector) -> VectorVel Inverse(self, arg: TwistVel) -> TwistVel Inverse(self, arg: Twist) -> TwistVel
-
R¶
-
Rot(rotvec: Vector, angle: doubleVel) → RotationVel¶
-
Rot2(rotvec: Vector, angle: doubleVel) → RotationVel¶
-
RotX(angle: doubleVel) → RotationVel¶
-
RotY(angle: doubleVel) → RotationVel¶
-
RotZ(angle: doubleVel) → RotationVel¶
-
UnitX(self) → VectorVel¶
-
UnitY(self) → VectorVel¶
-
UnitZ(self) → VectorVel¶
-
deriv(self) → Vector¶
-
value(self) → Rotation¶
-
w¶
-
-
class
PyKDL.RotationalInertia(Ixx: float = 0, Iyy: float = 0, Izz: float = 0, Ixy: float = 0, Ixz: float = 0, Iyz: float = 0)¶ RotationalInertia(RotationalInertia)
-
Zero() → RotationalInertia¶
-
-
class
PyKDL.Segment(name: object, joint: Joint = Joint(Joint.None), f_tip: Frame = Frame.Identity(), I: RigidBodyInertia = RigidBodyInertia.Zero())¶ Segment(joint: Joint = Joint(Joint.None), f_tip: Frame = Frame.Identity(), I: RigidBodyInertia = RigidBodyInertia.Zero()) Segment(in_: Segment)
-
getFrameToTip(self) → Frame¶
-
getInertia(self) → RigidBodyInertia¶
-
getJoint(self) → Joint¶
-
getName(self) → object¶
-
pose(self, q: float) → Frame¶
-
setInertia(self, Iin: RigidBodyInertia)¶
-
twist(self, q: float, qdot: float) → Twist¶
-
-
PyKDL.SetToZero(v: Vector)¶ SetToZero(v: Twist) SetToZero(v: Wrench) SetToZero(array: JntArray) SetToZero(array: JntArrayVel) SetToZero(jac: Jacobian) SetToZero(v: TwistVel) SetToZero(matrix: JntSpaceInertiaMatrix)
-
PyKDL.Subtract(src1: JntArray, src2: JntArray, dest: JntArray)¶ Subtract(src1: JntArrayVel, src2: JntArrayVel, dest: JntArrayVel) Subtract(src1: JntArrayVel, src2: JntArray, dest: JntArrayVel) Subtract(src1: JntSpaceInertiaMatrix, src2: JntSpaceInertiaMatrix, dest: JntSpaceInertiaMatrix)
-
class
PyKDL.Tree(root_name: object = "root")¶ Tree(Tree)
-
addSegment(self, segment: Segment, hook_name: object) → bool¶
-
getChain(self, chain_root: object, chain_tip: object) → Chain¶
-
getNrOfJoints(self) → int¶
-
getNrOfSegments(self) → int¶
-
-
class
PyKDL.Twist¶ Twist(_vel: Vector, _rot: Vector) Twist(Twist)
-
RefPoint(self, v_base_AB: Vector) → Twist¶
-
ReverseSign(self)¶
-
Zero() → Twist¶
-
rot¶
-
vel¶
-
-
class
PyKDL.TwistVel¶ TwistVel(_vel: VectorVel, _rot: VectorVel) TwistVel(p: Twist, v: Twist) TwistVel(p: Twist) TwistVel(TwistVel)
-
GetTwist(self) → Twist¶
-
GetTwistDot(self) → Twist¶
-
RefPoint(self, v_base_AB: VectorVel) → TwistVel¶
-
ReverseSign(self)¶
-
Zero() → TwistVel¶
-
deriv(self) → Twist¶
-
rot¶
-
value(self) → Twist¶
-
vel¶
-
-
class
PyKDL.Vector¶ Vector(x: float, y: float, z: float) Vector(arg: Vector)
-
Norm(self) → float¶
-
Normalize(self, eps: float = epsilon) → float¶
-
ReverseSign(self)¶
-
Zero() → Vector¶
-
x(self, float)¶ x(self) -> float
-
y(self, float)¶ y(self) -> float
-
z(self, float)¶ z(self) -> float
-
-
class
PyKDL.VectorVel¶ VectorVel(_p: Vector, _v: Vector) VectorVel(_p: Vector) VectorVel(VectorVel)
-
Norm(self) → doubleVel¶
-
ReverseSign(self)¶
-
Zero() → VectorVel¶
-
deriv(self) → Vector¶
-
p¶
-
v¶
-
value(self) → Vector¶
-
-
class
PyKDL.Wrench¶ Wrench(force: Vector, torque: Vector) Wrench(Wrench)
-
RefPoint(self, v_base_AB: Vector) → Wrench¶
-
ReverseSign(self)¶
-
Zero() → Wrench¶
-
force¶
-
torque¶
-
-
PyKDL.addDelta(a: Vector, da: Vector, dt: float = 1) → Vector¶ addDelta(a: Rotation, da: Vector, dt: float = 1) -> Rotation addDelta(a: Frame, da: Twist, dt: float = 1) -> Frame addDelta(a: Twist, da: Twist, dt: float = 1) -> Twist addDelta(a: Wrench, da: Wrench, dt: float = 1) -> Wrench addDelta(a: doubleVel, da: doubleVel, dt: float = 1) -> doubleVel addDelta(a: VectorVel, da: VectorVel, dt: float = 1) -> VectorVel addDelta(a: RotationVel, da: VectorVel, dt: float = 1) -> RotationVel addDelta(a: FrameVel, da: TwistVel, dt: float = 1) -> FrameVel
-
PyKDL.changeBase(src1: Jacobian, rot: Rotation, dest: Jacobian)¶
-
PyKDL.changeRefFrame(src1: Jacobian, frame: Frame, dest: Jacobian)¶
-
PyKDL.changeRefPoint(src1: Jacobian, base_AB: Vector, dest: Jacobian)¶
-
PyKDL.diff(a: Vector, b: Vector, dt: float = 1) → Vector¶ diff(R_a_b1: Rotation, R_a_b2: Rotation, dt: float = 1) -> Vector diff(F_a_b1: Frame, F_a_b2: Frame, dt: float = 1) -> Twist diff(a: Twist, b: Twist, dt: float = 1) -> Twist diff(W_a_p1: Wrench, W_a_p2: Wrench, dt: float = 1) -> Wrench diff(a: doubleVel, b: doubleVel, dt: float = 1) -> doubleVel diff(a: VectorVel, b: VectorVel, dt: float = 1) -> VectorVel diff(a: RotationVel, b: RotationVel, dt: float = 1) -> VectorVel diff(a: FrameVel, b: FrameVel, dt: float = 1) -> TwistVel
-
PyKDL.dot(lhs: Vector, rhs: Vector) → float¶ dot(lhs: Twist, rhs: Wrench) -> float dot(rhs: Wrench, lhs: Twist) -> float dot(lhs: VectorVel, rhs: VectorVel) -> doubleVel dot(lhs: VectorVel, rhs: Vector) -> doubleVel dot(lhs: Vector, rhs: VectorVel) -> doubleVel