Classes | Typedefs | Functions | Variables
KDL Namespace Reference

Classes

class  ArticulatedBodyInertia
 6D Inertia of a articulated body More...
class  Chain
 This class encapsulates a serial kinematic interconnection structure. It is build out of segments. More...
class  ChainDynParam
class  ChainFkSolverAcc
 This abstract class encapsulates a solver for the forward acceleration kinematics for a KDL::Chain. More...
class  ChainFkSolverPos
 This abstract class encapsulates a solver for the forward position kinematics for a KDL::Chain. More...
class  ChainFkSolverPos_recursive
class  ChainFkSolverVel
 This abstract class encapsulates a solver for the forward velocity kinematics for a KDL::Chain. More...
class  ChainFkSolverVel_recursive
class  ChainIdSolver
 This abstract class encapsulates the inverse dynamics solver for a KDL::Chain. More...
class  ChainIdSolver_RNE
 Recursive newton euler inverse dynamics solver. More...
class  ChainIdSolver_Vereshchagin
 Dynamics calculations by constraints based on Vereshchagin 1989. for a chain. This class creates instance of hybrid dynamics solver. The solver calculates total joint space accelerations in a chain when a constraint force(s) is applied to the chain's end-effector (task space/cartesian space). More...
class  ChainIkSolverAcc
 This abstract class encapsulates the inverse acceleration solver for a KDL::Chain. More...
class  ChainIkSolverPos
 This abstract class encapsulates the inverse position solver for a KDL::Chain. More...
class  ChainIkSolverPos_LMA
 Solver for the inverse position kinematics that uses Levenberg-Marquardt. More...
class  ChainIkSolverPos_NR
class  ChainIkSolverPos_NR_JL
class  ChainIkSolverVel
 This abstract class encapsulates the inverse velocity solver for a KDL::Chain. More...
class  ChainIkSolverVel_pinv
class  ChainIkSolverVel_pinv_givens
class  ChainIkSolverVel_pinv_nso
class  ChainIkSolverVel_wdls
class  ChainJntToJacSolver
 Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers. It should not be used outside of KDL. More...
class  checkBinary
class  checkBinary_displ
class  checkBinaryVel
class  checkUnary
class  checkUnaryVel
class  Error
class  Error_BasicIO
class  Error_BasicIO_Exp_Delim
class  Error_BasicIO_File
class  Error_BasicIO_Not_A_Space
class  Error_BasicIO_Not_Opened
class  Error_BasicIO_ToBig
class  Error_BasicIO_Unexpected
class  Error_Chain_Unexpected_id
class  Error_ChainIO
class  Error_Criterium
class  Error_Criterium_Unexpected_id
class  Error_Frame_Frame_Unexpected_id
class  Error_Frame_Rotation_Unexpected_id
class  Error_Frame_Vector_Unexpected_id
class  Error_FrameIO
class  Error_Integrator
 Abstract subclass of all errors that can be thrown by Adaptive_Integrator. More...
class  Error_IO
class  Error_Limits
class  Error_Limits_Unexpected_id
class  Error_MotionIO
class  Error_MotionIO_Unexpected_MotProf
class  Error_MotionIO_Unexpected_Traj
class  Error_MotionPlanning
class  Error_MotionPlanning_Circle_No_Plane
class  Error_MotionPlanning_Circle_ToSmall
class  Error_MotionPlanning_Incompatible
class  Error_MotionPlanning_Not_Applicable
class  Error_MotionPlanning_Not_Feasible
class  Error_Not_Implemented
class  Error_Redundancy
class  Error_Redundancy_Illegal_Resolutiontype
class  Error_Redundancy_Low_Manip
class  Error_Redundancy_Unavoidable
class  Error_RedundancyIO
 Error_Redundancy indicates an error that occured during solving for redundancy. More...
class  Error_Stepsize_To_Small
 Error_Stepsize_To_Small is thrown if the stepsize becomes to small. More...
class  Error_Stepsize_Underflow
 Error_Stepsize_Underflow is thrown if the stepsize becomes to small. More...
class  Error_To_Many_Steps
class  Frame
 represents a frame transformation in 3D space (rotation + translation) More...
class  Frame2
class  FrameAcc
class  FrameVel
class  Jacobian
class  JntArrayAcc
class  JntArrayVel
class  Joint
 This class encapsulates a simple joint, that is with one parameterized degree of freedom and with scalar dynamic properties. More...
class  Path
class  Path_Circle
class  Path_Composite
class  Path_Cyclic_Closed
class  Path_Line
class  Path_Point
class  Path_RoundedComposite
class  Rall1d
class  Rall2d
class  RigidBodyInertia
 6D Inertia of a rigid body More...
class  Rotation
 represents rotations in 3 dimensional space. More...
class  Rotation2
class  RotationAcc
class  RotationalInertia
class  RotationalInterpolation
class  RotationalInterpolation_SingleAxis
class  RotationVel
class  Segment
 This class encapsulates a simple segment, that is a "rigid body" (i.e., a frame and a rigid body inertia) with a joint and with "handles", root and tip to connect to other segments. More...
class  SolverI
class  Stiffness
class  SVD_HH
class  TI
class  TI< double >
class  TI< int >
class  Trajectory
class  Trajectory_Composite
class  Trajectory_Segment
class  Trajectory_Stationary
class  Tree
 This class encapsulates a tree kinematic interconnection structure. It is build out of segments. More...
class  TreeElement
class  TreeFkSolverPos
 This abstract class encapsulates a solver for the forward position kinematics for a KDL::Tree. More...
class  TreeFkSolverPos_recursive
class  TreeIkSolverPos
 This abstract class encapsulates the inverse position solver for a KDL::Chain. More...
class  TreeIkSolverPos_NR_JL
class  TreeIkSolverPos_Online
class  TreeIkSolverVel
 This abstract class encapsulates the inverse velocity solver for a KDL::Tree. More...
class  TreeIkSolverVel_wdls
class  TreeJntToJacSolver
class  Twist
 represents both translational and rotational velocities. More...
class  TwistAcc
class  TwistVel
class  Vector
 A concrete implementation of a 3 dimensional vector class. More...
class  Vector2
 2D version of Vector More...
class  VectorAcc
class  VectorVel
class  VelocityProfile
class  VelocityProfile_Dirac
class  VelocityProfile_Rectangular
class  VelocityProfile_Spline
 A spline VelocityProfile trajectory interpolation. More...
class  VelocityProfile_Trap
class  VelocityProfile_TrapHalf
class  Wrench
 represents both translational and rotational acceleration. More...

Typedefs

typedef Rall2d< double, double,
double > 
doubleAcc
typedef Rall1d< double > doubleVel
typedef std::map< std::string,
Frame
Frames
typedef std::map< std::string,
Jacobian
Jacobians
typedef std::map< std::string,
TreeElement
SegmentMap
typedef TreeElement TreeElementType
typedef std::map< std::string,
Twist
Twists
typedef std::vector< WrenchWrenches

Functions

void _check_istream (std::istream &is)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > abs (const Rall1d< T, V, S > &x)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > abs (const Rall2d< T, V, S > &x)
double acos (double a)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > acos (const Rall1d< T, V, S > &x)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > acos (const Rall2d< T, V, S > &arg)
void Add (const JntArrayVel &src1, const JntArrayVel &src2, JntArrayVel &dest)
void Add (const JntArrayVel &src1, const JntArray &src2, JntArrayVel &dest)
void Add (const JntArrayAcc &src1, const JntArrayAcc &src2, JntArrayAcc &dest)
void Add (const JntArrayAcc &src1, const JntArrayVel &src2, JntArrayAcc &dest)
void Add (const JntArrayAcc &src1, const JntArray &src2, JntArrayAcc &dest)
void Add (const JntSpaceInertiaMatrix &src1, const JntSpaceInertiaMatrix &src2, JntSpaceInertiaMatrix &dest)
void Add (const JntArray &src1, const JntArray &src2, JntArray &dest)
IMETHOD doubleVel addDelta (const doubleVel &a, const doubleVel &da, double dt=1.0)
double addDelta (double a, double da, double dt)
IMETHOD VectorVel addDelta (const VectorVel &a, const VectorVel &da, double dt=1.0)
IMETHOD RotationVel addDelta (const RotationVel &a, const VectorVel &da, double dt=1.0)
IMETHOD FrameVel addDelta (const FrameVel &a, const TwistVel &da, double dt=1.0)
IMETHOD Vector addDelta (const Vector &p_w_a, const Vector &p_w_da, double dt=1)
 adds vector da to vector a. see also the corresponding diff() routine.
IMETHOD Rotation addDelta (const Rotation &R_w_a, const Vector &da_w, double dt=1)
IMETHOD Frame addDelta (const Frame &F_w_a, const Twist &da_w, double dt=1)
IMETHOD Twist addDelta (const Twist &a, const Twist &da, double dt=1)
 adds the twist da to the twist a. see also the corresponding diff() routine.
IMETHOD Wrench addDelta (const Wrench &a, const Wrench &da, double dt=1)
 adds the wrench da to the wrench w. see also the corresponding diff() routine. see also the corresponding diff() routine.
double asin (double a)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > asin (const Rall1d< T, V, S > &x)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > asin (const Rall2d< T, V, S > &arg)
double atan (double a)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > atan (const Rall1d< T, V, S > &x)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > atan (const Rall2d< T, V, S > &x)
double atan2 (double a, double b)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > atan2 (const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > atan2 (const Rall2d< T, V, S > &y, const Rall2d< T, V, S > &x)
bool changeBase (const Jacobian &src1, const Rotation &rot, Jacobian &dest)
bool changeRefFrame (const Jacobian &src1, const Frame &frame, Jacobian &dest)
bool changeRefPoint (const Jacobian &src1, const Vector &base_AB, Jacobian &dest)
void checkDiffs ()
void checkDoubleOps ()
template<typename T >
void checkEqual (const T &a, const T &b, double eps)
void checkEulerZYX ()
void checkFrameOps ()
void checkFrameVelOps ()
double cos (double a)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > cos (const Rall1d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > cos (const Rall2d< T, V, S > &arg)
double cosh (double a)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > cosh (const Rall1d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > cosh (const Rall2d< T, V, S > &arg)
IMETHOD doubleVel diff (const doubleVel &a, const doubleVel &b, double dt=1.0)
double diff (double a, double b, double dt)
IMETHOD VectorVel diff (const VectorVel &a, const VectorVel &b, double dt=1.0)
IMETHOD VectorVel diff (const RotationVel &a, const RotationVel &b, double dt=1.0)
IMETHOD TwistVel diff (const FrameVel &a, const FrameVel &b, double dt=1.0)
IMETHOD Vector diff (const Vector &p_w_a, const Vector &p_w_b, double dt=1)
IMETHOD Vector diff (const Rotation &R_a_b1, const Rotation &R_a_b2, double dt=1)
IMETHOD Twist diff (const Frame &F_a_b1, const Frame &F_a_b2, double dt=1)
IMETHOD Twist diff (const Twist &a, const Twist &b, double dt=1)
IMETHOD Wrench diff (const Wrench &W_a_p1, const Wrench &W_a_p2, double dt=1)
void Divide (const JntArrayVel &src, const double &factor, JntArrayVel &dest)
void Divide (const JntSpaceInertiaMatrix &src, const double &factor, JntSpaceInertiaMatrix &dest)
void Divide (const JntArray &src, const double &factor, JntArray &dest)
void Divide (const JntArrayVel &src, const doubleVel &factor, JntArrayVel &dest)
void Divide (const JntArrayAcc &src, const double &factor, JntArrayAcc &dest)
void Divide (const JntArrayAcc &src, const doubleVel &factor, JntArrayAcc &dest)
void Divide (const JntArrayAcc &src, const doubleAcc &factor, JntArrayAcc &dest)
doubleAcc dot (const VectorAcc &lhs, const VectorAcc &rhs)
doubleAcc dot (const VectorAcc &lhs, const Vector &rhs)
doubleAcc dot (const Vector &lhs, const VectorAcc &rhs)
IMETHOD doubleVel dot (const VectorVel &lhs, const VectorVel &rhs)
IMETHOD doubleVel dot (const VectorVel &lhs, const Vector &rhs)
IMETHOD doubleVel dot (const Vector &lhs, const VectorVel &rhs)
void Eat (std::istream &is, int delim)
void Eat (std::istream &is, const char *descript)
void EatEnd (std::istream &is, int delim)
void EatWord (std::istream &is, const char *delim, char *storage, int maxsize)
IMETHOD bool Equal (const FrameAcc &r1, const FrameAcc &r2, double eps=epsilon)
IMETHOD bool Equal (const Frame &r1, const FrameAcc &r2, double eps=epsilon)
IMETHOD bool Equal (const FrameAcc &r1, const Frame &r2, double eps=epsilon)
IMETHOD bool Equal (const RotationAcc &r1, const RotationAcc &r2, double eps=epsilon)
IMETHOD bool Equal (const Rotation &r1, const RotationAcc &r2, double eps=epsilon)
IMETHOD bool Equal (const RotationAcc &r1, const Rotation &r2, double eps=epsilon)
IMETHOD bool Equal (const TwistAcc &a, const TwistAcc &b, double eps=epsilon)
IMETHOD bool Equal (const Twist &a, const TwistAcc &b, double eps=epsilon)
IMETHOD bool Equal (const TwistAcc &a, const Twist &b, double eps=epsilon)
IMETHOD bool Equal (const VectorAcc &r1, const VectorAcc &r2, double eps=epsilon)
IMETHOD bool Equal (const Vector &r1, const VectorAcc &r2, double eps=epsilon)
IMETHOD bool Equal (const VectorAcc &r1, const Vector &r2, double eps=epsilon)
IMETHOD bool Equal (const VectorVel &r1, const VectorVel &r2, double eps=epsilon)
IMETHOD bool Equal (const Vector &r1, const VectorVel &r2, double eps=epsilon)
IMETHOD bool Equal (const VectorVel &r1, const Vector &r2, double eps=epsilon)
IMETHOD bool Equal (const RotationVel &r1, const RotationVel &r2, double eps=epsilon)
IMETHOD bool Equal (const Rotation &r1, const RotationVel &r2, double eps=epsilon)
IMETHOD bool Equal (const RotationVel &r1, const Rotation &r2, double eps=epsilon)
IMETHOD bool Equal (const FrameVel &r1, const FrameVel &r2, double eps=epsilon)
IMETHOD bool Equal (const Frame &r1, const FrameVel &r2, double eps=epsilon)
IMETHOD bool Equal (const FrameVel &r1, const Frame &r2, double eps=epsilon)
IMETHOD bool Equal (const TwistVel &a, const TwistVel &b, double eps=epsilon)
IMETHOD bool Equal (const Twist &a, const TwistVel &b, double eps=epsilon)
IMETHOD bool Equal (const TwistVel &a, const Twist &b, double eps=epsilon)
bool Equal (const JntArrayVel &src1, const JntArrayVel &src2, double eps)
bool Equal (const JntSpaceInertiaMatrix &src1, const JntSpaceInertiaMatrix &src2, double eps)
bool Equal (const JntArray &src1, const JntArray &src2, double eps)
bool Equal (const Jacobian &a, const Jacobian &b, double eps)
bool Equal (const Vector &a, const Vector &b, double eps=epsilon)
bool Equal (const Frame &a, const Frame &b, double eps=epsilon)
bool Equal (const Twist &a, const Twist &b, double eps=epsilon)
bool Equal (const Wrench &a, const Wrench &b, double eps=epsilon)
bool Equal (const Vector2 &a, const Vector2 &b, double eps=epsilon)
bool Equal (const Rotation &a, const Rotation &b, double eps)
bool Equal (const Rotation2 &a, const Rotation2 &b, double eps=epsilon)
bool Equal (const Frame2 &a, const Frame2 &b, double eps=epsilon)
bool Equal (const JntArrayAcc &src1, const JntArrayAcc &src2, double eps)
bool Equal (double a, double b, double eps=epsilon)
template<class T , class V , class S >
INLINE bool Equal (const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x, double eps=epsilon)
template<class T , class V , class S >
INLINE bool Equal (const Rall2d< T, V, S > &y, const Rall2d< T, V, S > &x, double eps=epsilon)
double exp (double a)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > exp (const Rall1d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > exp (const Rall2d< T, V, S > &arg)
static void generatePowers (int n, double x, double *powers)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > hypot (const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > hypot (const Rall2d< T, V, S > &y, const Rall2d< T, V, S > &x)
void IOTrace (const std::string &description)
void IOTraceOutput (std::ostream &os)
 outputs the IO-stack to a stream to provide a better errormessage.
void IOTracePop ()
 pops a description of the IO-stack
void IOTracePopStr (char *buffer, int size)
Chain KukaLWR ()
Chain KukaLWR_DHnew ()
Chain KukaLWRsegment ()
double LinComb (double alfa, double a, double beta, double b)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > LinComb (S alfa, const Rall1d< T, V, S > &a, const T &beta, const Rall1d< T, V, S > &b)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > LinComb (S alfa, const Rall2d< T, V, S > &a, const T &beta, const Rall2d< T, V, S > &b)
void LinCombR (double alfa, double a, double beta, double b, double &result)
template<class T , class V , class S >
INLINE void LinCombR (S alfa, const Rall1d< T, V, S > &a, const T &beta, const Rall1d< T, V, S > &b, Rall1d< T, V, S > &result)
template<class T , class V , class S >
INLINE void LinCombR (S alfa, const Rall2d< T, V, S > &a, const T &beta, const Rall2d< T, V, S > &b, Rall2d< T, V, S > &result)
double log (double a)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > log (const Rall1d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > log (const Rall2d< T, V, S > &arg)
double max (double a, double b)
double min (double a, double b)
void Multiply (const JntArrayVel &src, const double &factor, JntArrayVel &dest)
void Multiply (const JntArrayVel &src, const doubleVel &factor, JntArrayVel &dest)
void Multiply (const JntSpaceInertiaMatrix &src, const double &factor, JntSpaceInertiaMatrix &dest)
void Multiply (const JntArray &src, const double &factor, JntArray &dest)
void Multiply (const JntSpaceInertiaMatrix &src, const JntArray &vec, JntArray &dest)
void Multiply (const JntArrayAcc &src, const double &factor, JntArrayAcc &dest)
void Multiply (const JntArrayAcc &src, const doubleVel &factor, JntArrayAcc &dest)
void Multiply (const JntArrayAcc &src, const doubleAcc &factor, JntArrayAcc &dest)
void MultiplyJacobian (const Jacobian &jac, const JntArray &src, Twist &dest)
double Norm (double arg)
template<class T , class V , class S >
INLINENorm (const Rall1d< T, V, S > &value)
template<class T , class V , class S >
INLINENorm (const Rall2d< T, V, S > &value)
FrameVel operator* (const FrameVel &lhs, const FrameVel &rhs)
FrameVel operator* (const FrameVel &lhs, const Frame &rhs)
FrameVel operator* (const Frame &lhs, const FrameVel &rhs)
RigidBodyInertia operator* (double a, const RigidBodyInertia &I)
RotationalInertia operator* (double a, const RotationalInertia &I)
ArticulatedBodyInertia operator* (double a, const ArticulatedBodyInertia &I)
Wrench operator* (const RigidBodyInertia &I, const Twist &t)
VectorAcc operator* (const VectorAcc &r1, const VectorAcc &r2)
RigidBodyInertia operator* (const Frame &T, const RigidBodyInertia &I)
VectorAcc operator* (const VectorAcc &r1, const Vector &r2)
VectorAcc operator* (const Vector &r1, const VectorAcc &r2)
Wrench operator* (const ArticulatedBodyInertia &I, const Twist &t)
VectorAcc operator* (double r1, const VectorAcc &r2)
RigidBodyInertia operator* (const Rotation &M, const RigidBodyInertia &I)
VectorAcc operator* (const VectorAcc &r1, double r2)
ArticulatedBodyInertia operator* (const Frame &T, const ArticulatedBodyInertia &I)
VectorAcc operator* (const doubleAcc &r1, const VectorAcc &r2)
Wrench operator* (const Stiffness &s, const Twist &t)
VectorAcc operator* (const VectorAcc &r2, const doubleAcc &r1)
ArticulatedBodyInertia operator* (const Rotation &M, const ArticulatedBodyInertia &I)
RotationVel operator* (const RotationVel &r1, const RotationVel &r2)
RotationVel operator* (const Rotation &r1, const RotationVel &r2)
RotationVel operator* (const RotationVel &r1, const Rotation &r2)
Rotation operator* (const Rotation &lhs, const Rotation &rhs)
RotationAcc operator* (const RotationAcc &r1, const RotationAcc &r2)
RotationAcc operator* (const Rotation &r1, const RotationAcc &r2)
RotationAcc operator* (const RotationAcc &r1, const Rotation &r2)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator* (const Rall1d< T, V, S > &lhs, const Rall1d< T, V, S > &rhs)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator* (const Rall2d< T, V, S > &lhs, const Rall2d< T, V, S > &rhs)
VectorVel operator* (const VectorVel &r1, const VectorVel &r2)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator* (S s, const Rall1d< T, V, S > &v)
VectorVel operator* (const VectorVel &r1, const Vector &r2)
VectorVel operator* (const Vector &r1, const VectorVel &r2)
VectorAcc operator* (const Rotation &R, const VectorAcc &x)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator* (const Rall1d< T, V, S > &v, S s)
VectorVel operator* (double r1, const VectorVel &r2)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator* (S s, const Rall2d< T, V, S > &v)
VectorVel operator* (const VectorVel &r1, double r2)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator* (const Rall2d< T, V, S > &v, S s)
VectorVel operator* (const doubleVel &r1, const VectorVel &r2)
VectorVel operator* (const VectorVel &r2, const doubleVel &r1)
VectorVel operator* (const Rotation &R, const VectorVel &x)
FrameAcc operator* (const FrameAcc &lhs, const FrameAcc &rhs)
FrameAcc operator* (const FrameAcc &lhs, const Frame &rhs)
FrameAcc operator* (const Frame &lhs, const FrameAcc &rhs)
TwistVel operator* (const TwistVel &lhs, double rhs)
TwistVel operator* (double lhs, const TwistVel &rhs)
TwistVel operator* (const TwistVel &lhs, const doubleVel &rhs)
TwistVel operator* (const doubleVel &lhs, const TwistVel &rhs)
TwistAcc operator* (const TwistAcc &lhs, double rhs)
TwistAcc operator* (double lhs, const TwistAcc &rhs)
TwistAcc operator* (const TwistAcc &lhs, const doubleAcc &rhs)
TwistAcc operator* (const doubleAcc &lhs, const TwistAcc &rhs)
VectorAcc operator+ (const VectorAcc &r1, const VectorAcc &r2)
VectorAcc operator+ (const Vector &r1, const VectorAcc &r2)
VectorAcc operator+ (const VectorAcc &r1, const Vector &r2)
RigidBodyInertia operator+ (const RigidBodyInertia &Ia, const RigidBodyInertia &Ib)
ArticulatedBodyInertia operator+ (const ArticulatedBodyInertia &Ia, const ArticulatedBodyInertia &Ib)
RotationalInertia operator+ (const RotationalInertia &Ia, const RotationalInertia &Ib)
ArticulatedBodyInertia operator+ (const RigidBodyInertia &Ia, const ArticulatedBodyInertia &Ib)
Stiffness operator+ (const Stiffness &s1, const Stiffness &s2)
ArticulatedBodyInertia operator+ (const ArticulatedBodyInertia &Ia, const RigidBodyInertia &Ib)
VectorVel operator+ (const VectorVel &r1, const VectorVel &r2)
VectorVel operator+ (const VectorVel &r1, const Vector &r2)
VectorVel operator+ (const Vector &r1, const VectorVel &r2)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator+ (const Rall1d< T, V, S > &lhs, const Rall1d< T, V, S > &rhs)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator+ (const Rall2d< T, V, S > &lhs, const Rall2d< T, V, S > &rhs)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator+ (S s, const Rall1d< T, V, S > &v)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator+ (const Rall1d< T, V, S > &v, S s)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator+ (S s, const Rall2d< T, V, S > &v)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator+ (const Rall2d< T, V, S > &v, S s)
TwistVel operator+ (const TwistVel &lhs, const TwistVel &rhs)
TwistAcc operator+ (const TwistAcc &lhs, const TwistAcc &rhs)
VectorAcc operator- (const VectorAcc &r1, const VectorAcc &r2)
VectorAcc operator- (const Vector &r1, const VectorAcc &r2)
VectorAcc operator- (const VectorAcc &r1, const Vector &r2)
VectorAcc operator- (const VectorAcc &r)
ArticulatedBodyInertia operator- (const ArticulatedBodyInertia &Ia, const ArticulatedBodyInertia &Ib)
ArticulatedBodyInertia operator- (const RigidBodyInertia &Ia, const ArticulatedBodyInertia &Ib)
ArticulatedBodyInertia operator- (const ArticulatedBodyInertia &Ia, const RigidBodyInertia &Ib)
VectorVel operator- (const VectorVel &r1, const VectorVel &r2)
VectorVel operator- (const VectorVel &r1, const Vector &r2)
VectorVel operator- (const Vector &r1, const VectorVel &r2)
VectorVel operator- (const VectorVel &r)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator- (const Rall1d< T, V, S > &lhs, const Rall1d< T, V, S > &rhs)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator- (const Rall1d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator- (const Rall2d< T, V, S > &lhs, const Rall2d< T, V, S > &rhs)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator- (const Rall2d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator- (S s, const Rall1d< T, V, S > &v)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator- (const Rall1d< T, V, S > &v, S s)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator- (S s, const Rall2d< T, V, S > &v)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator- (const Rall2d< T, V, S > &v, S s)
TwistVel operator- (const TwistVel &lhs, const TwistVel &rhs)
TwistVel operator- (const TwistVel &arg)
TwistAcc operator- (const TwistAcc &lhs, const TwistAcc &rhs)
TwistAcc operator- (const TwistAcc &arg)
VectorAcc operator/ (const VectorAcc &r1, double r2)
VectorAcc operator/ (const VectorAcc &r2, const doubleAcc &r1)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator/ (const Rall1d< T, V, S > &lhs, const Rall1d< T, V, S > &rhs)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator/ (const Rall2d< T, V, S > &lhs, const Rall2d< T, V, S > &rhs)
VectorVel operator/ (const VectorVel &r1, double r2)
VectorVel operator/ (const VectorVel &r2, const doubleVel &r1)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator/ (S s, const Rall1d< T, V, S > &v)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > operator/ (const Rall1d< T, V, S > &v, S s)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator/ (S s, const Rall2d< T, V, S > &rhs)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > operator/ (const Rall2d< T, V, S > &v, S s)
TwistVel operator/ (const TwistVel &lhs, double rhs)
TwistVel operator/ (const TwistVel &lhs, const doubleVel &rhs)
TwistAcc operator/ (const TwistAcc &lhs, double rhs)
TwistAcc operator/ (const TwistAcc &lhs, const doubleAcc &rhs)
std::ostream & operator<< (std::ostream &os, const Joint &joint)
template<class T , class V , class S >
std::ostream & operator<< (std::ostream &os, const Rall1d< T, V, S > &r)
std::ostream & operator<< (std::ostream &os, const VectorVel &r)
template<class T , class V , class S >
std::ostream & operator<< (std::ostream &os, const Rall2d< T, V, S > &r)
std::ostream & operator<< (std::ostream &os, const VectorAcc &r)
std::ostream & operator<< (std::ostream &os, const RotationVel &r)
std::ostream & operator<< (std::ostream &os, const Segment &segment)
std::ostream & operator<< (std::ostream &os, const RotationAcc &r)
std::ostream & operator<< (std::ostream &os, const FrameVel &r)
std::ostream & operator<< (std::ostream &os, const Vector &v)
std::ostream & operator<< (std::ostream &os, const FrameAcc &r)
std::ostream & operator<< (std::ostream &os, const Chain &chain)
std::ostream & operator<< (std::ostream &os, const TwistVel &r)
std::ostream & operator<< (std::ostream &os, const TwistAcc &r)
std::ostream & operator<< (std::ostream &os, const Twist &v)
std::ostream & operator<< (std::ostream &os, const Tree &tree)
std::ostream & operator<< (std::ostream &os, const Wrench &v)
std::ostream & operator<< (std::ostream &os, SegmentMap::const_iterator root)
std::ostream & operator<< (std::ostream &os, const Rotation &R)
std::ostream & operator<< (std::ostream &os, const JntArray &array)
std::ostream & operator<< (std::ostream &os, const Jacobian &jac)
std::ostream & operator<< (std::ostream &os, const JntSpaceInertiaMatrix &jntspaceinertiamatrix)
std::ostream & operator<< (std::ostream &os, const Frame &T)
std::ostream & operator<< (std::ostream &os, const Vector2 &v)
std::ostream & operator<< (std::ostream &os, const Rotation2 &R)
std::ostream & operator<< (std::ostream &os, const Frame2 &T)
bool operator== (const JntSpaceInertiaMatrix &src1, const JntSpaceInertiaMatrix &src2)
bool operator== (const JntArray &src1, const JntArray &src2)
bool operator== (const Rotation &a, const Rotation &b)
std::istream & operator>> (std::istream &is, Joint &joint)
std::istream & operator>> (std::istream &is, Segment &segment)
std::istream & operator>> (std::istream &is, Chain &chain)
std::istream & operator>> (std::istream &is, Tree &tree)
std::istream & operator>> (std::istream &is, JntArray &array)
std::istream & operator>> (std::istream &is, Jacobian &jac)
std::istream & operator>> (std::istream &is, JntSpaceInertiaMatrix &jntspaceinertiamatrix)
std::istream & operator>> (std::istream &is, Vector &v)
std::istream & operator>> (std::istream &is, Twist &v)
std::istream & operator>> (std::istream &is, Wrench &v)
std::istream & operator>> (std::istream &is, Rotation &r)
std::istream & operator>> (std::istream &is, Frame &T)
std::istream & operator>> (std::istream &is, Vector2 &v)
std::istream & operator>> (std::istream &is, Rotation2 &r)
std::istream & operator>> (std::istream &is, Frame2 &T)
template<typename T >
void posrandom (Jacobian< T > &rv)
IMETHOD void posrandom (doubleVel &F)
void posrandom (Stiffness &F)
void posrandom (double &a)
IMETHOD void posrandom (VectorVel &a)
IMETHOD void posrandom (TwistVel &a)
IMETHOD void posrandom (RotationVel &R)
IMETHOD void posrandom (FrameVel &F)
double pow (double a, double b)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > pow (const Rall1d< T, V, S > &arg, double m)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > pow (const Rall2d< T, V, S > &arg, double m)
Chain Puma560 ()
double PYTHAG (double a, double b)
template<typename T >
void random (Jacobian< T > &rv)
IMETHOD void random (doubleVel &F)
void random (Stiffness &F)
void random (double &a)
IMETHOD void random (VectorVel &a)
IMETHOD void random (TwistVel &a)
IMETHOD void random (RotationVel &R)
IMETHOD void random (FrameVel &F)
void SetToIdentity (double &arg)
 to uniformly set double, RNDouble,Vector,... objects to the identity element in template-classes
template<class T , class V , class S >
INLINE void SetToIdentity (Rall1d< T, V, S > &value)
template<class T , class V , class S >
INLINE void SetToIdentity (Rall2d< T, V, S > &value)
void SetToZero (Jacobian &jac)
void SetToZero (JntArrayVel &array)
void SetToZero (JntSpaceInertiaMatrix &mat)
void SetToZero (JntArray &array)
void SetToZero (JntArrayAcc &array)
void SetToZero (double &arg)
 to uniformly set double, RNDouble,Vector,... objects to zero in template-classes
void SetToZero (VectorVel &v)
template<class T , class V , class S >
INLINE void SetToZero (Rall1d< T, V, S > &value)
void SetToZero (TwistVel &v)
template<class T , class V , class S >
INLINE void SetToZero (Rall2d< T, V, S > &value)
double SIGN (double a, double b)
double sign (double arg)
double sin (double a)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > sin (const Rall1d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > sin (const Rall2d< T, V, S > &arg)
double sinh (double a)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > sinh (const Rall1d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > sinh (const Rall2d< T, V, S > &arg)
double sqr (double arg)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > sqr (const Rall1d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > sqr (const Rall2d< T, V, S > &arg)
double sqrt (double a)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > sqrt (const Rall1d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > sqrt (const Rall2d< T, V, S > &arg)
void Subtract (const JntArrayVel &src1, const JntArrayVel &src2, JntArrayVel &dest)
void Subtract (const JntArrayVel &src1, const JntArray &src2, JntArrayVel &dest)
void Subtract (const JntArrayAcc &src1, const JntArrayAcc &src2, JntArrayAcc &dest)
void Subtract (const JntSpaceInertiaMatrix &src1, const JntSpaceInertiaMatrix &src2, JntSpaceInertiaMatrix &dest)
void Subtract (const JntArray &src1, const JntArray &src2, JntArray &dest)
void Subtract (const JntArrayAcc &src1, const JntArrayVel &src2, JntArrayAcc &dest)
void Subtract (const JntArrayAcc &src1, const JntArray &src2, JntArrayAcc &dest)
int svd_eigen_HH (const MatrixXd &A, MatrixXd &U, VectorXd &S, MatrixXd &V, VectorXd &tmp, int maxiter, double epsilon)
int svd_eigen_Macie (const MatrixXd &A, MatrixXd &U, VectorXd &S, MatrixXd &V, MatrixXd &B, VectorXd &tempi, double treshold, bool toggle)
double tan (double a)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > tan (const Rall1d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > tan (const Rall2d< T, V, S > &arg)
double tanh (double a)
template<class T , class V , class S >
INLINE Rall2d< T, V, S > tanh (const Rall2d< T, V, S > &arg)
template<class T , class V , class S >
INLINE Rall1d< T, V, S > tanh (const Rall1d< T, V, S > &arg)
template<typename Derived >
void Twist_to_Eigen (const KDL::Twist &t, Eigen::MatrixBase< Derived > &e)

Variables

const double deg2rad
 the value pi/180
double epsilon
 default precision while comparing with Equal(..,..) functions. Initialized at 0.0000001.
int MAXLENFILENAME
 maximal length of a file name
static const bool mhi = true
const double PI
 the value of pi
const double rad2deg
 the value 180/pi
int STREAMBUFFERSIZE
int VSIZE
 the number of derivatives used in the RN-... objects.

Typedef Documentation

typedef Rall2d<double,double,double> KDL::doubleAcc

Definition at line 40 of file frameacc.hpp.

typedef Rall1d<double> KDL::doubleVel

Definition at line 36 of file framevel.hpp.

typedef std::map<std::string, Frame> KDL::Frames

Definition at line 20 of file treeiksolver.hpp.

typedef std::map<std::string, Jacobian> KDL::Jacobians

Definition at line 19 of file treeiksolver.hpp.

typedef std::map<std::string,TreeElement> KDL::SegmentMap

Definition at line 39 of file tree.hpp.

Definition at line 57 of file tree.hpp.

typedef std::map<std::string, Twist> KDL::Twists

Definition at line 18 of file treeiksolver.hpp.

typedef std::vector<Wrench> KDL::Wrenches

Definition at line 32 of file chainidsolver.hpp.


Function Documentation

void KDL::_check_istream ( std::istream &  is)

checks validity of basic io of is

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::abs ( const Rall1d< T, V, S > &  x)

Definition at line 409 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::abs ( const Rall2d< T, V, S > &  x)

Definition at line 465 of file rall2d.h.

double KDL::acos ( double  a) [inline]

Definition at line 113 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::acos ( const Rall1d< T, V, S > &  x)

Definition at line 401 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::acos ( const Rall2d< T, V, S > &  arg)

Definition at line 429 of file rall2d.h.

void KDL::Add ( const JntArrayVel &  src1,
const JntArrayVel &  src2,
JntArrayVel &  dest 
)

Definition at line 57 of file jntarrayvel.cpp.

void KDL::Add ( const JntArrayVel &  src1,
const JntArray &  src2,
JntArrayVel &  dest 
)

Definition at line 62 of file jntarrayvel.cpp.

void KDL::Add ( const JntArrayAcc &  src1,
const JntArrayAcc &  src2,
JntArrayAcc &  dest 
)

Definition at line 66 of file jntarrayacc.cpp.

void KDL::Add ( const JntArrayAcc &  src1,
const JntArrayVel &  src2,
JntArrayAcc &  dest 
)

Definition at line 72 of file jntarrayacc.cpp.

void KDL::Add ( const JntArrayAcc &  src1,
const JntArray &  src2,
JntArrayAcc &  dest 
)

Definition at line 78 of file jntarrayacc.cpp.

void KDL::Add ( const JntSpaceInertiaMatrix &  src1,
const JntSpaceInertiaMatrix &  src2,
JntSpaceInertiaMatrix &  dest 
)

Definition at line 81 of file jntspaceinertiamatrix.cpp.

void KDL::Add ( const JntArray &  src1,
const JntArray &  src2,
JntArray &  dest 
)

Definition at line 82 of file jntarray.cpp.

IMETHOD doubleVel KDL::addDelta ( const doubleVel &  a,
const doubleVel &  da,
double  dt = 1.0 
)

Definition at line 42 of file framevel.hpp.

double KDL::addDelta ( double  a,
double  da,
double  dt 
) [inline]

Definition at line 282 of file utility.h.

IMETHOD VectorVel KDL::addDelta ( const VectorVel &  a,
const VectorVel &  da,
double  dt = 1.0 
)

Definition at line 327 of file framevel.hpp.

IMETHOD RotationVel KDL::addDelta ( const RotationVel &  a,
const VectorVel &  da,
double  dt = 1.0 
)

Definition at line 334 of file framevel.hpp.

IMETHOD FrameVel KDL::addDelta ( const FrameVel &  a,
const TwistVel &  da,
double  dt = 1.0 
)

Definition at line 342 of file framevel.hpp.

IMETHOD Vector KDL::addDelta ( const Vector &  p_w_a,
const Vector &  p_w_da,
double  dt = 1 
)

adds vector da to vector a. see also the corresponding diff() routine.

Parameters:
p_w_avector a expressed to some frame w.
p_w_davector da expressed to some frame w.
Returns:
the vector resulting from the displacement of vector a by vector da, expressed in the frame w.
IMETHOD Rotation KDL::addDelta ( const Rotation &  R_w_a,
const Vector &  da_w,
double  dt = 1 
)

returns the rotation matrix resulting from the rotation of frame a by the axis and angle specified with da_w.

see also the corresponding diff() routine.

Parameters:
R_w_aRotation matrix of frame a expressed to some frame w.
da_waxis and angle of the rotation expressed to some frame w.
Returns:
the rotation matrix resulting from the rotation of frame a by the axis and angle specified with da. The resulting rotation matrix is expressed with respect to frame w.
IMETHOD Frame KDL::addDelta ( const Frame &  F_w_a,
const Twist &  da_w,
double  dt = 1 
)

returns the frame resulting from the rotation of frame a by the axis and angle specified in da_w and the translation of the origin (also specified in da_w).

see also the corresponding diff() routine.

Parameters:
R_w_aRotation matrix of frame a expressed to some frame w.
da_waxis and angle of the rotation (da_w.rot), together with a displacement vector for the origin (da_w.vel), expressed to some frame w.
Returns:
the frame resulting from the rotation of frame a by the axis and angle specified with da.rot, and the translation of the origin da_w.vel . The resulting frame is expressed with respect to frame w.
IMETHOD Twist KDL::addDelta ( const Twist &  a,
const Twist &  da,
double  dt = 1 
)

adds the twist da to the twist a. see also the corresponding diff() routine.

Parameters:
aa twist wrt some frame
daa twist difference wrt some frame
Returns:
The twist (a+da) wrt the corresponding frame.
IMETHOD Wrench KDL::addDelta ( const Wrench &  a,
const Wrench &  da,
double  dt = 1 
)

adds the wrench da to the wrench w. see also the corresponding diff() routine. see also the corresponding diff() routine.

Parameters:
aa wrench wrt some frame
daa wrench difference wrt some frame
Returns:
the wrench (a+da) wrt the corresponding frame.
double KDL::asin ( double  a) [inline]

Definition at line 116 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::asin ( const Rall1d< T, V, S > &  x)

Definition at line 393 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::asin ( const Rall2d< T, V, S > &  arg)

Definition at line 417 of file rall2d.h.

double KDL::atan ( double  a) [inline]

Definition at line 110 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::atan ( const Rall1d< T, V, S > &  x)

Definition at line 377 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::atan ( const Rall2d< T, V, S > &  x)

Definition at line 442 of file rall2d.h.

double KDL::atan2 ( double  a,
double  b 
) [inline]

Definition at line 125 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::atan2 ( const Rall1d< T, V, S > &  y,
const Rall1d< T, V, S > &  x 
)

Definition at line 431 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::atan2 ( const Rall2d< T, V, S > &  y,
const Rall2d< T, V, S > &  x 
)

Definition at line 454 of file rall2d.h.

bool KDL::changeBase ( const Jacobian &  src1,
const Rotation &  rot,
Jacobian &  dest 
)

Definition at line 104 of file jacobian.cpp.

bool KDL::changeRefFrame ( const Jacobian &  src1,
const Frame &  frame,
Jacobian &  dest 
)

Definition at line 118 of file jacobian.cpp.

bool KDL::changeRefPoint ( const Jacobian &  src1,
const Vector &  base_AB,
Jacobian &  dest 
)

Definition at line 90 of file jacobian.cpp.

void KDL::checkDiffs ( )

Definition at line 13 of file jacobianframetests.cpp.

Definition at line 6 of file jacobiandoubletests.cpp.

template<typename T >
void KDL::checkEqual ( const T &  a,
const T &  b,
double  eps 
) [inline]

Definition at line 34 of file jacobiantests.hpp.

Definition at line 50 of file jacobianframetests.cpp.

Definition at line 89 of file jacobianframetests.cpp.

Definition at line 132 of file jacobianframetests.cpp.

double KDL::cos ( double  a) [inline]

Definition at line 89 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::cos ( const Rall1d< T, V, S > &  arg)

Definition at line 321 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::cos ( const Rall2d< T, V, S > &  arg)

Definition at line 346 of file rall2d.h.

double KDL::cosh ( double  a) [inline]

Definition at line 101 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::cosh ( const Rall1d< T, V, S > &  arg)

Definition at line 345 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::cosh ( const Rall2d< T, V, S > &  arg)

Definition at line 370 of file rall2d.h.

IMETHOD doubleVel KDL::diff ( const doubleVel &  a,
const doubleVel &  b,
double  dt = 1.0 
)

Definition at line 38 of file framevel.hpp.

double KDL::diff ( double  a,
double  b,
double  dt 
) [inline]

Definition at line 276 of file utility.h.

IMETHOD VectorVel KDL::diff ( const VectorVel &  a,
const VectorVel &  b,
double  dt = 1.0 
)

Definition at line 323 of file framevel.hpp.

IMETHOD VectorVel KDL::diff ( const RotationVel &  a,
const RotationVel &  b,
double  dt = 1.0 
)

Definition at line 330 of file framevel.hpp.

IMETHOD TwistVel KDL::diff ( const FrameVel &  a,
const FrameVel &  b,
double  dt = 1.0 
)

Definition at line 338 of file framevel.hpp.

IMETHOD Vector KDL::diff ( const Vector &  p_w_a,
const Vector &  p_w_b,
double  dt = 1 
)

determines the difference of vector b with vector a.

see diff for Rotation matrices for further background information.

Parameters:
p_w_astart vector a expressed to some frame w
p_w_bend vector b expressed to some frame w .
dt[optional][obsolete] time interval over which the numerical differentiation takes place.
Returns:
the difference (b-a) expressed to the frame w.
IMETHOD Vector KDL::diff ( const Rotation &  R_a_b1,
const Rotation &  R_a_b2,
double  dt = 1 
)

determines the (scaled) rotation axis necessary to rotate from b1 to b2.

This rotation axis is expressed w.r.t. frame a. The rotation axis is scaled by the necessary rotation angle. The rotation angle is always in the (inclusive) interval $ [0 , \pi] $.

This definition is chosen in this way to facilitate numerical differentiation. With this definition diff(a,b) == -diff(b,a).

The diff() function is overloaded for all classes in frames.hpp and framesvel.hpp, such that numerical differentiation, equality checks with tolerances, etc. can be performed without caring exactly on which type the operation is performed.

Parameters:
R_a_b1,:The rotation matrix $ _a^{b1} R $ of b1 with respect to frame a.
R_a_b2,:The Rotation matrix $ _a^{b2} R $ of b2 with respect to frame a.
dt[optional][obsolete] time interval over which the numerical differentiation takes place. By default this is set to 1.0.
Returns:
rotation axis to rotate from b1 to b2, scaled by the rotation angle, expressed in frame a.
Warning:
- The result is not a rotational vector, i.e. it is not a mathematical vector. (no communitative addition).
- When used in the context of numerical differentiation, with the frames b1 and b2 very close to each other, the semantics correspond to the twist, scaled by the time.
- For angles equal to $ \pi $, The negative of the return value is equally valid.
IMETHOD Twist KDL::diff ( const Frame &  F_a_b1,
const Frame &  F_a_b2,
double  dt = 1 
)

determines the rotation axis necessary to rotate the frame b1 to the same orientation as frame b2 and the vector necessary to translate the origin of b1 to the origin of b2, and stores the result in a Twist datastructure.

Parameters:
F_a_b1frame b1 expressed with respect to some frame a.
F_a_b2frame b2 expressed with respect to some frame a.
Warning:
The result is not a Twist! see diff() for Rotation and Vector arguments for further detail on the semantics.
IMETHOD Twist KDL::diff ( const Twist &  a,
const Twist &  b,
double  dt = 1 
)

determines the difference between two twists i.e. the difference between the underlying velocity vectors and rotational velocity vectors.

IMETHOD Wrench KDL::diff ( const Wrench &  W_a_p1,
const Wrench &  W_a_p2,
double  dt = 1 
)

determines the difference between two wrenches i.e. the difference between the underlying torque vectors and force vectors.

void KDL::Divide ( const JntArrayVel &  src,
const double &  factor,
JntArrayVel &  dest 
)

Definition at line 92 of file jntarrayvel.cpp.

void KDL::Divide ( const JntSpaceInertiaMatrix &  src,
const double &  factor,
JntSpaceInertiaMatrix &  dest 
)

Definition at line 96 of file jntspaceinertiamatrix.cpp.

void KDL::Divide ( const JntArray &  src,
const double &  factor,
JntArray &  dest 
)

Definition at line 97 of file jntarray.cpp.

void KDL::Divide ( const JntArrayVel &  src,
const doubleVel &  factor,
JntArrayVel &  dest 
)

Definition at line 97 of file jntarrayvel.cpp.

void KDL::Divide ( const JntArrayAcc &  src,
const double &  factor,
JntArrayAcc &  dest 
)

Definition at line 133 of file jntarrayacc.cpp.

void KDL::Divide ( const JntArrayAcc &  src,
const doubleVel &  factor,
JntArrayAcc &  dest 
)

Definition at line 139 of file jntarrayacc.cpp.

void KDL::Divide ( const JntArrayAcc &  src,
const doubleAcc &  factor,
JntArrayAcc &  dest 
)

Definition at line 151 of file jntarrayacc.cpp.

doubleAcc KDL::dot ( const VectorAcc &  lhs,
const VectorAcc &  rhs 
)

Definition at line 138 of file frameacc.hpp.

doubleAcc KDL::dot ( const VectorAcc &  lhs,
const Vector &  rhs 
)

Definition at line 145 of file frameacc.hpp.

doubleAcc KDL::dot ( const Vector &  lhs,
const VectorAcc &  rhs 
)

Definition at line 152 of file frameacc.hpp.

IMETHOD doubleVel KDL::dot ( const VectorVel &  lhs,
const VectorVel &  rhs 
)

Definition at line 358 of file framevel.hpp.

IMETHOD doubleVel KDL::dot ( const VectorVel &  lhs,
const Vector &  rhs 
)

Definition at line 361 of file framevel.hpp.

IMETHOD doubleVel KDL::dot ( const Vector &  lhs,
const VectorVel &  rhs 
)

Definition at line 364 of file framevel.hpp.

void KDL::Eat ( std::istream &  is,
int  delim 
)

Eats characters of the stream until the character delim is encountered

Parameters:
isa stream
delimeat until this character is encountered
void KDL::Eat ( std::istream &  is,
const char *  descript 
)

Eats characters of the stream as long as they satisfy the description in descript

Parameters:
isa stream
descriptdescription string. A sequence of spaces, tabs, new-lines and comments is regarded as 1 space in the description string.
void KDL::EatEnd ( std::istream &  is,
int  delim 
)

Eats characters of the stream until the character delim is encountered similar to Eat(is,delim) but spaces at the end are not read.

Parameters:
isa stream
delimeat until this character is encountered
void KDL::EatWord ( std::istream &  is,
const char *  delim,
char *  storage,
int  maxsize 
)

Eats a word of the stream delimited by the letters in delim or space(tabs...)

Parameters:
isa stream
delima string containing the delimmiting characters
storagefor returning the word
maxsizea word can be maximally maxsize-1 long.
bool KDL::Equal ( const FrameAcc &  r1,
const FrameAcc &  r2,
double  eps = epsilon 
)

Definition at line 394 of file frameacc.hpp.

bool KDL::Equal ( const Frame &  r1,
const FrameAcc &  r2,
double  eps = epsilon 
)

Definition at line 397 of file frameacc.hpp.

bool KDL::Equal ( const FrameAcc &  r1,
const Frame &  r2,
double  eps = epsilon 
)

Definition at line 400 of file frameacc.hpp.

bool KDL::Equal ( const RotationAcc &  r1,
const RotationAcc &  r2,
double  eps = epsilon 
)

Definition at line 324 of file frameacc.hpp.

bool KDL::Equal ( const Rotation &  r1,
const RotationAcc &  r2,
double  eps = epsilon 
)

Definition at line 327 of file frameacc.hpp.

bool KDL::Equal ( const RotationAcc &  r1,
const Rotation &  r2,
double  eps = epsilon 
)

Definition at line 331 of file frameacc.hpp.

bool KDL::Equal ( const TwistAcc &  a,
const TwistAcc &  b,
double  eps = epsilon 
)

Definition at line 587 of file frameacc.hpp.

bool KDL::Equal ( const Twist &  a,
const TwistAcc &  b,
double  eps = epsilon 
)

Definition at line 591 of file frameacc.hpp.

bool KDL::Equal ( const TwistAcc &  a,
const Twist &  b,
double  eps = epsilon 
)

Definition at line 595 of file frameacc.hpp.

bool KDL::Equal ( const VectorAcc &  r1,
const VectorAcc &  r2,
double  eps = epsilon 
)

Definition at line 160 of file frameacc.hpp.

bool KDL::Equal ( const Vector &  r1,
const VectorAcc &  r2,
double  eps = epsilon 
)

Definition at line 167 of file frameacc.hpp.

bool KDL::Equal ( const VectorAcc &  r1,
const Vector &  r2,
double  eps = epsilon 
)

Definition at line 174 of file frameacc.hpp.

bool KDL::Equal ( const VectorVel &  r1,
const VectorVel &  r2,
double  eps = epsilon 
)

Definition at line 324 of file framevel.hpp.

bool KDL::Equal ( const Vector &  r1,
const VectorVel &  r2,
double  eps = epsilon 
)

Definition at line 327 of file framevel.hpp.

bool KDL::Equal ( const VectorVel &  r1,
const Vector &  r2,
double  eps = epsilon 
)

Definition at line 330 of file framevel.hpp.

bool KDL::Equal ( const RotationVel &  r1,
const RotationVel &  r2,
double  eps = epsilon 
)

Definition at line 334 of file framevel.hpp.

bool KDL::Equal ( const Rotation &  r1,
const RotationVel &  r2,
double  eps = epsilon 
)

Definition at line 337 of file framevel.hpp.

bool KDL::Equal ( const RotationVel &  r1,
const Rotation &  r2,
double  eps = epsilon 
)

Definition at line 340 of file framevel.hpp.

bool KDL::Equal ( const FrameVel &  r1,
const FrameVel &  r2,
double  eps = epsilon 
)

Definition at line 76 of file framevel.hpp.

bool KDL::Equal ( const Frame &  r1,
const FrameVel &  r2,
double  eps = epsilon 
)

Definition at line 79 of file framevel.hpp.

bool KDL::Equal ( const FrameVel &  r1,
const Frame &  r2,
double  eps = epsilon 
)

Definition at line 82 of file framevel.hpp.

bool KDL::Equal ( const TwistVel &  a,
const TwistVel &  b,
double  eps = epsilon 
)

Definition at line 343 of file framevel.hpp.

bool KDL::Equal ( const Twist &  a,
const TwistVel &  b,
double  eps = epsilon 
)

Definition at line 347 of file framevel.hpp.

bool KDL::Equal ( const TwistVel &  a,
const Twist &  b,
double  eps = epsilon 
)

Definition at line 351 of file framevel.hpp.

bool KDL::Equal ( const JntArrayVel &  src1,
const JntArrayVel &  src2,
double  eps 
)

Definition at line 111 of file jntarrayvel.cpp.

bool KDL::Equal ( const JntSpaceInertiaMatrix &  src1,
const JntSpaceInertiaMatrix &  src2,
double  eps 
)

Definition at line 111 of file jntspaceinertiamatrix.cpp.

bool KDL::Equal ( const JntArray &  src1,
const JntArray &  src2,
double  eps 
)

Definition at line 113 of file jntarray.cpp.

bool KDL::Equal ( const Jacobian &  a,
const Jacobian &  b,
double  eps 
)

Definition at line 137 of file jacobian.cpp.

bool KDL::Equal ( const Vector &  a,
const Vector &  b,
double  eps = epsilon 
) [inline]

do not use operator == because the definition of Equal(.,.) is slightly different. It compares whether the 2 arguments are equal in an eps-interval

bool KDL::Equal ( const Frame &  a,
const Frame &  b,
double  eps = epsilon 
) [inline]

do not use operator == because the definition of Equal(.,.) is slightly different. It compares whether the 2 arguments are equal in an eps-interval

bool KDL::Equal ( const Twist &  a,
const Twist &  b,
double  eps = epsilon 
) [inline]

do not use operator == because the definition of Equal(.,.) is slightly different. It compares whether the 2 arguments are equal in an eps-interval

bool KDL::Equal ( const Wrench &  a,
const Wrench &  b,
double  eps = epsilon 
) [inline]

do not use operator == because the definition of Equal(.,.) is slightly different. It compares whether the 2 arguments are equal in an eps-interval

bool KDL::Equal ( const Vector2 &  a,
const Vector2 &  b,
double  eps = epsilon 
) [inline]

do not use operator == because the definition of Equal(.,.) is slightly different. It compares whether the 2 arguments are equal in an eps-interval

bool KDL::Equal ( const Rotation &  a,
const Rotation &  b,
double  eps 
)

do not use operator == because the definition of Equal(.,.) is slightly different. It compares whether the 2 arguments are equal in an eps-interval

Definition at line 153 of file frames.cpp.

bool KDL::Equal ( const Rotation2 &  a,
const Rotation2 &  b,
double  eps = epsilon 
) [inline]

do not use operator == because the definition of Equal(.,.) is slightly different. It compares whether the 2 arguments are equal in an eps-interval

bool KDL::Equal ( const Frame2 &  a,
const Frame2 &  b,
double  eps = epsilon 
) [inline]
bool KDL::Equal ( const JntArrayAcc &  src1,
const JntArrayAcc &  src2,
double  eps 
)

Definition at line 171 of file jntarrayacc.cpp.

bool KDL::Equal ( double  a,
double  b,
double  eps = epsilon 
) [inline]

Definition at line 262 of file utility.h.

template<class T , class V , class S >
INLINE bool KDL::Equal ( const Rall1d< T, V, S > &  y,
const Rall1d< T, V, S > &  x,
double  eps = epsilon 
)

Definition at line 469 of file rall1d.h.

template<class T , class V , class S >
INLINE bool KDL::Equal ( const Rall2d< T, V, S > &  y,
const Rall2d< T, V, S > &  x,
double  eps = epsilon 
)

Definition at line 526 of file rall2d.h.

double KDL::exp ( double  a) [inline]

Definition at line 92 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::exp ( const Rall1d< T, V, S > &  arg)

Definition at line 297 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::exp ( const Rall2d< T, V, S > &  arg)

Definition at line 318 of file rall2d.h.

static void KDL::generatePowers ( int  n,
double  x,
double *  powers 
) [inline, static]

Definition at line 8 of file velocityprofile_spline.cpp.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::hypot ( const Rall1d< T, V, S > &  y,
const Rall1d< T, V, S > &  x 
)

Definition at line 385 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::hypot ( const Rall2d< T, V, S > &  y,
const Rall2d< T, V, S > &  x 
)

Definition at line 472 of file rall2d.h.

void KDL::IOTrace ( const std::string &  description)
void KDL::IOTraceOutput ( std::ostream &  os)

outputs the IO-stack to a stream to provide a better errormessage.

void KDL::IOTracePop ( )

pops a description of the IO-stack

void KDL::IOTracePopStr ( char *  buffer,
int  size 
)

outputs one element of the IO-stack to the buffer (maximally size chars) returns empty string if no elements on the stack.

Definition at line 26 of file kukaLWR_DHnew.cpp.

double KDL::LinComb ( double  alfa,
double  a,
double  beta,
double  b 
) [inline]

Definition at line 225 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::LinComb ( alfa,
const Rall1d< T, V, S > &  a,
const T &  beta,
const Rall1d< T, V, S > &  b 
)

Definition at line 439 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::LinComb ( alfa,
const Rall2d< T, V, S > &  a,
const T &  beta,
const Rall2d< T, V, S > &  b 
)

Definition at line 492 of file rall2d.h.

void KDL::LinCombR ( double  alfa,
double  a,
double  beta,
double  b,
double &  result 
) [inline]

Definition at line 230 of file utility.h.

template<class T , class V , class S >
INLINE void KDL::LinCombR ( alfa,
const Rall1d< T, V, S > &  a,
const T &  beta,
const Rall1d< T, V, S > &  b,
Rall1d< T, V, S > &  result 
)

Definition at line 448 of file rall1d.h.

template<class T , class V , class S >
INLINE void KDL::LinCombR ( alfa,
const Rall2d< T, V, S > &  a,
const T &  beta,
const Rall2d< T, V, S > &  b,
Rall2d< T, V, S > &  result 
)

Definition at line 502 of file rall2d.h.

double KDL::log ( double  a) [inline]

Definition at line 95 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::log ( const Rall1d< T, V, S > &  arg)

Definition at line 305 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::log ( const Rall2d< T, V, S > &  arg)

Definition at line 328 of file rall2d.h.

double KDL::max ( double  a,
double  b 
) [inline]

Definition at line 198 of file utility.h.

double KDL::min ( double  a,
double  b 
) [inline]

Definition at line 206 of file utility.h.

void KDL::Multiply ( const JntArrayVel &  src,
const double &  factor,
JntArrayVel &  dest 
)

Definition at line 79 of file jntarrayvel.cpp.

void KDL::Multiply ( const JntArrayVel &  src,
const doubleVel &  factor,
JntArrayVel &  dest 
)

Definition at line 84 of file jntarrayvel.cpp.

void KDL::Multiply ( const JntSpaceInertiaMatrix &  src,
const double &  factor,
JntSpaceInertiaMatrix &  dest 
)

Definition at line 91 of file jntspaceinertiamatrix.cpp.

void KDL::Multiply ( const JntArray &  src,
const double &  factor,
JntArray &  dest 
)

Definition at line 92 of file jntarray.cpp.

void KDL::Multiply ( const JntSpaceInertiaMatrix &  src,
const JntArray &  vec,
JntArray &  dest 
)

Definition at line 101 of file jntspaceinertiamatrix.cpp.

void KDL::Multiply ( const JntArrayAcc &  src,
const double &  factor,
JntArrayAcc &  dest 
)

Definition at line 104 of file jntarrayacc.cpp.

void KDL::Multiply ( const JntArrayAcc &  src,
const doubleVel &  factor,
JntArrayAcc &  dest 
)

Definition at line 110 of file jntarrayacc.cpp.

void KDL::Multiply ( const JntArrayAcc &  src,
const doubleAcc &  factor,
JntArrayAcc &  dest 
)

Definition at line 120 of file jntarrayacc.cpp.

void KDL::MultiplyJacobian ( const Jacobian &  jac,
const JntArray &  src,
Twist &  dest 
)

Definition at line 102 of file jntarray.cpp.

double KDL::Norm ( double  arg) [inline]

Definition at line 250 of file utility.h.

template<class T , class V , class S >
INLINE S KDL::Norm ( const Rall1d< T, V, S > &  value)

Definition at line 418 of file rall1d.h.

template<class T , class V , class S >
INLINE S KDL::Norm ( const Rall2d< T, V, S > &  value)

Definition at line 483 of file rall2d.h.

FrameVel KDL::operator* ( const FrameVel &  lhs,
const FrameVel &  rhs 
)

Definition at line 34 of file framevel.hpp.

FrameVel KDL::operator* ( const FrameVel &  lhs,
const Frame &  rhs 
)

Definition at line 38 of file framevel.hpp.

FrameVel KDL::operator* ( const Frame &  lhs,
const FrameVel &  rhs 
)

Definition at line 42 of file framevel.hpp.

RigidBodyInertia KDL::operator* ( double  a,
const RigidBodyInertia &  I 
)

Scalar product: I_new = double * I_old

Definition at line 44 of file rigidbodyinertia.cpp.

RotationalInertia KDL::operator* ( double  a,
const RotationalInertia &  I 
)

Definition at line 50 of file rotationalinertia.cpp.

ArticulatedBodyInertia KDL::operator* ( double  a,
const ArticulatedBodyInertia &  I 
)

Scalar product: I_new = double * I_old

Definition at line 51 of file articulatedbodyinertia.cpp.

Wrench KDL::operator* ( const RigidBodyInertia &  I,
const Twist &  t 
)

calculate spatial momentum: h = I*v make sure that the twist v and the inertia are expressed in the same reference frame/point

Definition at line 52 of file rigidbodyinertia.cpp.

VectorAcc KDL::operator* ( const VectorAcc &  r1,
const VectorAcc &  r2 
)

Definition at line 53 of file frameacc.hpp.

RigidBodyInertia KDL::operator* ( const Frame &  T,
const RigidBodyInertia &  I 
)

Coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b.

Definition at line 56 of file rigidbodyinertia.cpp.

VectorAcc KDL::operator* ( const VectorAcc &  r1,
const Vector &  r2 
)

Definition at line 60 of file frameacc.hpp.

VectorAcc KDL::operator* ( const Vector &  r1,
const VectorAcc &  r2 
)

Definition at line 64 of file frameacc.hpp.

Wrench KDL::operator* ( const ArticulatedBodyInertia &  I,
const Twist &  t 
)

calculate spatial momentum: h = I*v make sure that the twist v and the inertia are expressed in the same reference frame/point

Definition at line 70 of file articulatedbodyinertia.cpp.

VectorAcc KDL::operator* ( double  r1,
const VectorAcc &  r2 
)

Definition at line 71 of file frameacc.hpp.

RigidBodyInertia KDL::operator* ( const Rotation &  R,
const RigidBodyInertia &  I 
)

Reference frame orientation change Ia = R_a_b*Ib with R_a_b the rotation of b expressed in a

Definition at line 74 of file rigidbodyinertia.cpp.

VectorAcc KDL::operator* ( const VectorAcc &  r1,
double  r2 
)

Definition at line 75 of file frameacc.hpp.

ArticulatedBodyInertia KDL::operator* ( const Frame &  T,
const ArticulatedBodyInertia &  I 
)

Coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b.

Definition at line 77 of file articulatedbodyinertia.cpp.

VectorAcc KDL::operator* ( const doubleAcc &  r1,
const VectorAcc &  r2 
)

Definition at line 79 of file frameacc.hpp.

Wrench KDL::operator* ( const Stiffness &  s,
const Twist &  t 
) [inline]

Definition at line 81 of file stiffness.hpp.

VectorAcc KDL::operator* ( const VectorAcc &  r2,
const doubleAcc &  r1 
)

Definition at line 86 of file frameacc.hpp.

ArticulatedBodyInertia KDL::operator* ( const Rotation &  R,
const ArticulatedBodyInertia &  I 
)

Reference frame orientation change Ia = R_a_b*Ib with R_a_b the rotation of b expressed in a

Definition at line 92 of file articulatedbodyinertia.cpp.

RotationVel KDL::operator* ( const RotationVel &  r1,
const RotationVel &  r2 
)

Definition at line 95 of file framevel.hpp.

RotationVel KDL::operator* ( const Rotation &  r1,
const RotationVel &  r2 
)

Definition at line 99 of file framevel.hpp.

RotationVel KDL::operator* ( const RotationVel &  r1,
const Rotation &  r2 
)

Definition at line 103 of file framevel.hpp.

Rotation KDL::operator* ( const Rotation &  lhs,
const Rotation &  rhs 
)

Definition at line 167 of file frames.cpp.

RotationAcc KDL::operator* ( const RotationAcc &  r1,
const RotationAcc &  r2 
)

Definition at line 193 of file frameacc.hpp.

RotationAcc KDL::operator* ( const Rotation &  r1,
const RotationAcc &  r2 
)

Definition at line 200 of file frameacc.hpp.

RotationAcc KDL::operator* ( const RotationAcc &  r1,
const Rotation &  r2 
)

Definition at line 204 of file frameacc.hpp.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator* ( const Rall1d< T, V, S > &  lhs,
const Rall1d< T, V, S > &  rhs 
)

Definition at line 223 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator* ( const Rall2d< T, V, S > &  lhs,
const Rall2d< T, V, S > &  rhs 
)

Definition at line 236 of file rall2d.h.

VectorVel KDL::operator* ( const VectorVel &  r1,
const VectorVel &  r2 
)

Definition at line 246 of file framevel.hpp.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator* ( s,
const Rall1d< T, V, S > &  v 
)

Definition at line 248 of file rall1d.h.

VectorVel KDL::operator* ( const VectorVel &  r1,
const Vector &  r2 
)

Definition at line 250 of file framevel.hpp.

VectorVel KDL::operator* ( const Vector &  r1,
const VectorVel &  r2 
)

Definition at line 254 of file framevel.hpp.

VectorAcc KDL::operator* ( const Rotation &  R,
const VectorAcc &  x 
)

Definition at line 255 of file frameacc.hpp.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator* ( const Rall1d< T, V, S > &  v,
s 
)

Definition at line 254 of file rall1d.h.

VectorVel KDL::operator* ( double  r1,
const VectorVel &  r2 
)

Definition at line 261 of file framevel.hpp.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator* ( s,
const Rall2d< T, V, S > &  v 
)

Definition at line 264 of file rall2d.h.

VectorVel KDL::operator* ( const VectorVel &  r1,
double  r2 
)

Definition at line 265 of file framevel.hpp.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator* ( const Rall2d< T, V, S > &  v,
s 
)

Definition at line 270 of file rall2d.h.

VectorVel KDL::operator* ( const doubleVel &  r1,
const VectorVel &  r2 
)

Definition at line 271 of file framevel.hpp.

VectorVel KDL::operator* ( const VectorVel &  r2,
const doubleVel &  r1 
)

Definition at line 275 of file framevel.hpp.

VectorVel KDL::operator* ( const Rotation &  R,
const VectorVel &  x 
)

Definition at line 287 of file framevel.hpp.

FrameAcc KDL::operator* ( const FrameAcc &  lhs,
const FrameAcc &  rhs 
)

Definition at line 350 of file frameacc.hpp.

FrameAcc KDL::operator* ( const FrameAcc &  lhs,
const Frame &  rhs 
)

Definition at line 354 of file frameacc.hpp.

FrameAcc KDL::operator* ( const Frame &  lhs,
const FrameAcc &  rhs 
)

Definition at line 358 of file frameacc.hpp.

TwistVel KDL::operator* ( const TwistVel &  lhs,
double  rhs 
)

Definition at line 416 of file framevel.hpp.

TwistVel KDL::operator* ( double  lhs,
const TwistVel &  rhs 
)

Definition at line 421 of file framevel.hpp.

TwistVel KDL::operator* ( const TwistVel &  lhs,
const doubleVel &  rhs 
)

Definition at line 432 of file framevel.hpp.

TwistVel KDL::operator* ( const doubleVel &  lhs,
const TwistVel &  rhs 
)

Definition at line 437 of file framevel.hpp.

TwistAcc KDL::operator* ( const TwistAcc &  lhs,
double  rhs 
)

Definition at line 472 of file frameacc.hpp.

TwistAcc KDL::operator* ( double  lhs,
const TwistAcc &  rhs 
)

Definition at line 477 of file frameacc.hpp.

TwistAcc KDL::operator* ( const TwistAcc &  lhs,
const doubleAcc &  rhs 
)

Definition at line 488 of file frameacc.hpp.

TwistAcc KDL::operator* ( const doubleAcc &  lhs,
const TwistAcc &  rhs 
)

Definition at line 493 of file frameacc.hpp.

VectorAcc KDL::operator+ ( const VectorAcc &  r1,
const VectorAcc &  r2 
)

Definition at line 25 of file frameacc.hpp.

VectorAcc KDL::operator+ ( const Vector &  r1,
const VectorAcc &  r2 
)

Definition at line 32 of file frameacc.hpp.

VectorAcc KDL::operator+ ( const VectorAcc &  r1,
const Vector &  r2 
)

Definition at line 39 of file frameacc.hpp.

RigidBodyInertia KDL::operator+ ( const RigidBodyInertia &  Ia,
const RigidBodyInertia &  Ib 
)

addition I: I_new = I_old1 + I_old2, make sure that I_old1 and I_old2 are expressed in the same reference frame/point, otherwise the result is worth nothing

Definition at line 48 of file rigidbodyinertia.cpp.

ArticulatedBodyInertia KDL::operator+ ( const ArticulatedBodyInertia &  Ia,
const ArticulatedBodyInertia &  Ib 
)

addition I: I_new = I_old1 + I_old2, make sure that I_old1 and I_old2 are expressed in the same reference frame/point, otherwise the result is worth nothing

Definition at line 55 of file articulatedbodyinertia.cpp.

RotationalInertia KDL::operator+ ( const RotationalInertia &  Ia,
const RotationalInertia &  Ib 
)

Definition at line 56 of file rotationalinertia.cpp.

ArticulatedBodyInertia KDL::operator+ ( const RigidBodyInertia &  Ia,
const ArticulatedBodyInertia &  Ib 
)

Definition at line 59 of file articulatedbodyinertia.cpp.

Stiffness KDL::operator+ ( const Stiffness &  s1,
const Stiffness &  s2 
) [inline]

Definition at line 92 of file stiffness.hpp.

ArticulatedBodyInertia KDL::operator+ ( const ArticulatedBodyInertia &  Ia,
const RigidBodyInertia &  Ib 
)
VectorVel KDL::operator+ ( const VectorVel &  r1,
const VectorVel &  r2 
)

Definition at line 211 of file framevel.hpp.

VectorVel KDL::operator+ ( const VectorVel &  r1,
const Vector &  r2 
)

Definition at line 219 of file framevel.hpp.

VectorVel KDL::operator+ ( const Vector &  r1,
const VectorVel &  r2 
)

Definition at line 227 of file framevel.hpp.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator+ ( const Rall1d< T, V, S > &  lhs,
const Rall1d< T, V, S > &  rhs 
)

Definition at line 229 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator+ ( const Rall2d< T, V, S > &  lhs,
const Rall2d< T, V, S > &  rhs 
)

Definition at line 246 of file rall2d.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator+ ( s,
const Rall1d< T, V, S > &  v 
)

Definition at line 260 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator+ ( const Rall1d< T, V, S > &  v,
s 
)

Definition at line 266 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator+ ( s,
const Rall2d< T, V, S > &  v 
)

Definition at line 276 of file rall2d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator+ ( const Rall2d< T, V, S > &  v,
s 
)

Definition at line 282 of file rall2d.h.

TwistVel KDL::operator+ ( const TwistVel &  lhs,
const TwistVel &  rhs 
)

Definition at line 450 of file framevel.hpp.

TwistAcc KDL::operator+ ( const TwistAcc &  lhs,
const TwistAcc &  rhs 
)

Definition at line 506 of file frameacc.hpp.

VectorAcc KDL::operator- ( const VectorAcc &  r1,
const VectorAcc &  r2 
)

Definition at line 29 of file frameacc.hpp.

VectorAcc KDL::operator- ( const Vector &  r1,
const VectorAcc &  r2 
)

Definition at line 36 of file frameacc.hpp.

VectorAcc KDL::operator- ( const VectorAcc &  r1,
const Vector &  r2 
)

Definition at line 43 of file frameacc.hpp.

VectorAcc KDL::operator- ( const VectorAcc &  r)

Definition at line 48 of file frameacc.hpp.

ArticulatedBodyInertia KDL::operator- ( const ArticulatedBodyInertia &  Ia,
const ArticulatedBodyInertia &  Ib 
)

Definition at line 62 of file articulatedbodyinertia.cpp.

ArticulatedBodyInertia KDL::operator- ( const RigidBodyInertia &  Ia,
const ArticulatedBodyInertia &  Ib 
)

Definition at line 66 of file articulatedbodyinertia.cpp.

ArticulatedBodyInertia KDL::operator- ( const ArticulatedBodyInertia &  Ia,
const RigidBodyInertia &  Ib 
)
VectorVel KDL::operator- ( const VectorVel &  r1,
const VectorVel &  r2 
)

Definition at line 215 of file framevel.hpp.

VectorVel KDL::operator- ( const VectorVel &  r1,
const Vector &  r2 
)

Definition at line 223 of file framevel.hpp.

VectorVel KDL::operator- ( const Vector &  r1,
const VectorVel &  r2 
)

Definition at line 231 of file framevel.hpp.

VectorVel KDL::operator- ( const VectorVel &  r)

Definition at line 236 of file framevel.hpp.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator- ( const Rall1d< T, V, S > &  lhs,
const Rall1d< T, V, S > &  rhs 
)

Definition at line 236 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator- ( const Rall1d< T, V, S > &  arg)

Definition at line 242 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator- ( const Rall2d< T, V, S > &  lhs,
const Rall2d< T, V, S > &  rhs 
)

Definition at line 252 of file rall2d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator- ( const Rall2d< T, V, S > &  arg)

Definition at line 258 of file rall2d.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator- ( s,
const Rall1d< T, V, S > &  v 
)

Definition at line 272 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator- ( const Rall1d< T, V, S > &  v,
s 
)

Definition at line 278 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator- ( s,
const Rall2d< T, V, S > &  v 
)

Definition at line 288 of file rall2d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator- ( const Rall2d< T, V, S > &  v,
s 
)

Definition at line 294 of file rall2d.h.

TwistVel KDL::operator- ( const TwistVel &  lhs,
const TwistVel &  rhs 
)

Definition at line 455 of file framevel.hpp.

TwistVel KDL::operator- ( const TwistVel &  arg)

Definition at line 461 of file framevel.hpp.

TwistAcc KDL::operator- ( const TwistAcc &  lhs,
const TwistAcc &  rhs 
)

Definition at line 511 of file frameacc.hpp.

TwistAcc KDL::operator- ( const TwistAcc &  arg)

Definition at line 517 of file frameacc.hpp.

VectorAcc KDL::operator/ ( const VectorAcc &  r1,
double  r2 
)

Definition at line 181 of file frameacc.hpp.

VectorAcc KDL::operator/ ( const VectorAcc &  r2,
const doubleAcc &  r1 
)

Definition at line 185 of file frameacc.hpp.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator/ ( const Rall1d< T, V, S > &  lhs,
const Rall1d< T, V, S > &  rhs 
)

Definition at line 217 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator/ ( const Rall2d< T, V, S > &  lhs,
const Rall2d< T, V, S > &  rhs 
)

Definition at line 226 of file rall2d.h.

VectorVel KDL::operator/ ( const VectorVel &  r1,
double  r2 
)

Definition at line 279 of file framevel.hpp.

VectorVel KDL::operator/ ( const VectorVel &  r2,
const doubleVel &  r1 
)

Definition at line 283 of file framevel.hpp.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator/ ( s,
const Rall1d< T, V, S > &  v 
)

Definition at line 284 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::operator/ ( const Rall1d< T, V, S > &  v,
s 
)

Definition at line 290 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator/ ( s,
const Rall2d< T, V, S > &  rhs 
)

Definition at line 300 of file rall2d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::operator/ ( const Rall2d< T, V, S > &  v,
s 
)

Definition at line 311 of file rall2d.h.

TwistVel KDL::operator/ ( const TwistVel &  lhs,
double  rhs 
)

Definition at line 426 of file framevel.hpp.

TwistVel KDL::operator/ ( const TwistVel &  lhs,
const doubleVel &  rhs 
)

Definition at line 442 of file framevel.hpp.

TwistAcc KDL::operator/ ( const TwistAcc &  lhs,
double  rhs 
)

Definition at line 482 of file frameacc.hpp.

TwistAcc KDL::operator/ ( const TwistAcc &  lhs,
const doubleAcc &  rhs 
)

Definition at line 498 of file frameacc.hpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Joint &  joint 
)

Definition at line 26 of file kinfam_io.cpp.

template<class T , class V , class S >
std::ostream& KDL::operator<< ( std::ostream &  os,
const Rall1d< T, V, S > &  r 
) [inline]

Definition at line 27 of file rall1d_io.h.

std::ostream& KDL::operator<< ( std::ostream &  os,
const VectorVel &  r 
) [inline]

Definition at line 30 of file framevel_io.hpp.

template<class T , class V , class S >
std::ostream& KDL::operator<< ( std::ostream &  os,
const Rall2d< T, V, S > &  r 
)

Definition at line 29 of file rall2d_io.h.

std::ostream& KDL::operator<< ( std::ostream &  os,
const VectorAcc &  r 
) [inline]

Definition at line 32 of file frameacc_io.hpp.

std::ostream& KDL::operator<< ( std::ostream &  os,
const RotationVel &  r 
) [inline]

Definition at line 35 of file framevel_io.hpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Segment &  segment 
)

Definition at line 35 of file kinfam_io.cpp.

std::ostream& KDL::operator<< ( std::ostream &  os,
const RotationAcc &  r 
) [inline]

Definition at line 37 of file frameacc_io.hpp.

std::ostream& KDL::operator<< ( std::ostream &  os,
const FrameVel &  r 
) [inline]

Definition at line 41 of file framevel_io.hpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Vector &  v 
)

width to be used when printing variables out with frames_io.h global variable, can be changed.

Definition at line 42 of file frames_io.cpp.

std::ostream& KDL::operator<< ( std::ostream &  os,
const FrameAcc &  r 
) [inline]

Definition at line 44 of file frameacc_io.hpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Chain &  chain 
)

Definition at line 44 of file kinfam_io.cpp.

std::ostream& KDL::operator<< ( std::ostream &  os,
const TwistVel &  r 
) [inline]

Definition at line 46 of file framevel_io.hpp.

std::ostream& KDL::operator<< ( std::ostream &  os,
const TwistAcc &  r 
) [inline]

Definition at line 48 of file frameacc_io.hpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Twist &  v 
)

Definition at line 48 of file frames_io.cpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Tree &  tree 
)

Definition at line 56 of file kinfam_io.cpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Wrench &  v 
)

Definition at line 59 of file frames_io.cpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
SegmentMap::const_iterator  root 
)

Definition at line 61 of file kinfam_io.cpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Rotation &  R 
)

Definition at line 71 of file frames_io.cpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const JntArray &  array 
)

Definition at line 74 of file kinfam_io.cpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Jacobian &  jac 
)

Definition at line 86 of file kinfam_io.cpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const JntSpaceInertiaMatrix &  jntspaceinertiamatrix 
)

Definition at line 100 of file kinfam_io.cpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Frame &  T 
)

Definition at line 105 of file frames_io.cpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Vector2 &  v 
)

Definition at line 111 of file frames_io.cpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Rotation2 &  R 
)

Definition at line 118 of file frames_io.cpp.

std::ostream & KDL::operator<< ( std::ostream &  os,
const Frame2 &  T 
)

Definition at line 123 of file frames_io.cpp.

bool KDL::operator== ( const JntSpaceInertiaMatrix &  src1,
const JntSpaceInertiaMatrix &  src2 
)

Definition at line 118 of file jntspaceinertiamatrix.cpp.

bool KDL::operator== ( const JntArray &  src1,
const JntArray &  src2 
)

Definition at line 120 of file jntarray.cpp.

bool KDL::operator== ( const Rotation &  a,
const Rotation &  b 
)

Definition at line 388 of file frames.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Joint &  joint 
)

Definition at line 31 of file kinfam_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Segment &  segment 
)

Definition at line 40 of file kinfam_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Chain &  chain 
)

Definition at line 52 of file kinfam_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Tree &  tree 
)

Definition at line 70 of file kinfam_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
JntArray &  array 
)

Definition at line 82 of file kinfam_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Jacobian &  jac 
)

Definition at line 97 of file kinfam_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
JntSpaceInertiaMatrix &  jntspaceinertiamatrix 
)

Definition at line 111 of file kinfam_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Vector &  v 
)

Definition at line 129 of file frames_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Twist &  v 
)

Definition at line 152 of file frames_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Wrench &  v 
)

Definition at line 171 of file frames_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Rotation &  r 
)

Definition at line 190 of file frames_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Frame &  T 
)

Definition at line 251 of file frames_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Vector2 &  v 
)

Definition at line 282 of file frames_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Rotation2 &  r 
)

Definition at line 292 of file frames_io.cpp.

std::istream & KDL::operator>> ( std::istream &  is,
Frame2 &  T 
)

Definition at line 302 of file frames_io.cpp.

template<typename T >
void KDL::posrandom ( Jacobian< T > &  rv)

Definition at line 25 of file jacobiantests.hpp.

IMETHOD void KDL::posrandom ( doubleVel &  F)

Definition at line 50 of file framevel.hpp.

void KDL::posrandom ( Stiffness &  F) [inline]

Definition at line 102 of file stiffness.hpp.

void KDL::posrandom ( double &  a) [inline]

Definition at line 272 of file utility.h.

IMETHOD void KDL::posrandom ( VectorVel &  a)

Definition at line 367 of file framevel.hpp.

IMETHOD void KDL::posrandom ( TwistVel &  a)

Definition at line 371 of file framevel.hpp.

IMETHOD void KDL::posrandom ( RotationVel &  R)

Definition at line 376 of file framevel.hpp.

IMETHOD void KDL::posrandom ( FrameVel &  F)

Definition at line 381 of file framevel.hpp.

double KDL::pow ( double  a,
double  b 
) [inline]

Definition at line 122 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::pow ( const Rall1d< T, V, S > &  arg,
double  m 
)

Definition at line 361 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::pow ( const Rall2d< T, V, S > &  arg,
double  m 
)

Definition at line 395 of file rall2d.h.

Definition at line 26 of file puma560.cpp.

double KDL::PYTHAG ( double  a,
double  b 
) [inline]

Definition at line 35 of file svd_eigen_HH.hpp.

template<typename T >
void KDL::random ( Jacobian< T > &  rv)

Definition at line 16 of file jacobiantests.hpp.

IMETHOD void KDL::random ( doubleVel &  F)

Definition at line 46 of file framevel.hpp.

void KDL::random ( Stiffness &  F) [inline]

Definition at line 111 of file stiffness.hpp.

void KDL::random ( double &  a) [inline]

Definition at line 268 of file utility.h.

IMETHOD void KDL::random ( VectorVel &  a)

Definition at line 349 of file framevel.hpp.

IMETHOD void KDL::random ( TwistVel &  a)

Definition at line 353 of file framevel.hpp.

IMETHOD void KDL::random ( RotationVel &  R)

Definition at line 358 of file framevel.hpp.

IMETHOD void KDL::random ( FrameVel &  F)

Definition at line 363 of file framevel.hpp.

void KDL::SetToIdentity ( double &  arg) [inline]

to uniformly set double, RNDouble,Vector,... objects to the identity element in template-classes

Definition at line 241 of file utility.h.

template<class T , class V , class S >
INLINE void KDL::SetToIdentity ( Rall1d< T, V, S > &  value)

Definition at line 462 of file rall1d.h.

template<class T , class V , class S >
INLINE void KDL::SetToIdentity ( Rall2d< T, V, S > &  value)

Definition at line 518 of file rall2d.h.

void KDL::SetToZero ( Jacobian &  jac)

Definition at line 80 of file jacobian.cpp.

void KDL::SetToZero ( JntArrayVel &  array)

Definition at line 105 of file jntarrayvel.cpp.

void KDL::SetToZero ( JntSpaceInertiaMatrix &  mat)

Definition at line 106 of file jntspaceinertiamatrix.cpp.

void KDL::SetToZero ( JntArray &  array)

Definition at line 108 of file jntarray.cpp.

void KDL::SetToZero ( JntArrayAcc &  array)

Definition at line 164 of file jntarrayacc.cpp.

void KDL::SetToZero ( double &  arg) [inline]

to uniformly set double, RNDouble,Vector,... objects to zero in template-classes

Definition at line 236 of file utility.h.

void KDL::SetToZero ( VectorVel &  v)

Definition at line 240 of file framevel.hpp.

template<class T , class V , class S >
INLINE void KDL::SetToZero ( Rall1d< T, V, S > &  value)

Definition at line 456 of file rall1d.h.

void KDL::SetToZero ( TwistVel &  v)

Definition at line 466 of file framevel.hpp.

template<class T , class V , class S >
INLINE void KDL::SetToZero ( Rall2d< T, V, S > &  value)

Definition at line 510 of file rall2d.h.

double KDL::SIGN ( double  a,
double  b 
) [inline]

Definition at line 53 of file svd_eigen_HH.hpp.

double KDL::sign ( double  arg) [inline]

Definition at line 245 of file utility.h.

double KDL::sin ( double  a) [inline]

Definition at line 85 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::sin ( const Rall1d< T, V, S > &  arg)

Definition at line 313 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::sin ( const Rall2d< T, V, S > &  arg)

Definition at line 338 of file rall2d.h.

double KDL::sinh ( double  a) [inline]

Definition at line 104 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::sinh ( const Rall1d< T, V, S > &  arg)

Definition at line 337 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::sinh ( const Rall2d< T, V, S > &  arg)

Definition at line 362 of file rall2d.h.

double KDL::sqr ( double  arg) [inline]

Definition at line 249 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::sqr ( const Rall1d< T, V, S > &  arg)

Definition at line 353 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::sqr ( const Rall2d< T, V, S > &  arg)

Definition at line 386 of file rall2d.h.

double KDL::sqrt ( double  a) [inline]

Definition at line 107 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::sqrt ( const Rall1d< T, V, S > &  arg)

Definition at line 369 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::sqrt ( const Rall2d< T, V, S > &  arg)

Definition at line 406 of file rall2d.h.

void KDL::Subtract ( const JntArrayVel &  src1,
const JntArrayVel &  src2,
JntArrayVel &  dest 
)

Definition at line 68 of file jntarrayvel.cpp.

void KDL::Subtract ( const JntArrayVel &  src1,
const JntArray &  src2,
JntArrayVel &  dest 
)

Definition at line 73 of file jntarrayvel.cpp.

void KDL::Subtract ( const JntArrayAcc &  src1,
const JntArrayAcc &  src2,
JntArrayAcc &  dest 
)

Definition at line 85 of file jntarrayacc.cpp.

void KDL::Subtract ( const JntSpaceInertiaMatrix &  src1,
const JntSpaceInertiaMatrix &  src2,
JntSpaceInertiaMatrix &  dest 
)

Definition at line 86 of file jntspaceinertiamatrix.cpp.

void KDL::Subtract ( const JntArray &  src1,
const JntArray &  src2,
JntArray &  dest 
)

Definition at line 87 of file jntarray.cpp.

void KDL::Subtract ( const JntArrayAcc &  src1,
const JntArrayVel &  src2,
JntArrayAcc &  dest 
)

Definition at line 91 of file jntarrayacc.cpp.

void KDL::Subtract ( const JntArrayAcc &  src1,
const JntArray &  src2,
JntArrayAcc &  dest 
)

Definition at line 97 of file jntarrayacc.cpp.

int KDL::svd_eigen_HH ( const MatrixXd &  A,
MatrixXd &  U,
VectorXd &  S,
MatrixXd &  V,
VectorXd &  tmp,
int  maxiter = 150,
double  epsilon = 1e-300 
)

svd calculation of eigen matrices

Parameters:
Amatrix<double>(mxn)
Umatrix<double>(mxn)
Svector<double> n
Vmatrix<double>(nxn)
tmpvector<double> n
maxiterdefaults to 150
Returns:
-2 if maxiter exceeded, 0 otherwise

Definition at line 26 of file svd_eigen_HH.cpp.

int KDL::svd_eigen_Macie ( const MatrixXd &  A,
MatrixXd &  U,
VectorXd &  S,
MatrixXd &  V,
MatrixXd &  B,
VectorXd &  tempi,
double  treshold,
bool  toggle 
)

svd_eigen_Macie provides Maciejewski implementation for SVD.

computes the singular value decomposition of a matrix A, such that A=U*Sm*V

(Maciejewski and Klein,1989) and (Braun, Ulrey, Maciejewski and Siegel,2002)

Parameters:
A[INPUT] is an $m \times n$-matrix, where $ m \geq n $.
S[OUTPUT] is an $n$-vector, representing the diagonal elements of the diagonal matrix Sm.
U[INPUT/OUTPUT] is an $m \times m$ orthonormal matrix.
V[INPUT/OUTPUT] is an $n \times n$ orthonormal matrix.
B[TEMPORARY] is an $m \times n$ matrix used for temporary storage.
tempi[TEMPORARY] is an $m$ vector used for temporary storage.
thresshold[INPUT] Thresshold to determine orthogonality.
toggle[INPUT] toggle this boolean variable on each call of this routine.
Returns:
number of sweeps.

Definition at line 59 of file svd_eigen_Macie.hpp.

double KDL::tan ( double  a) [inline]

Definition at line 98 of file utility.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::tan ( const Rall1d< T, V, S > &  arg)

Definition at line 329 of file rall1d.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::tan ( const Rall2d< T, V, S > &  arg)

Definition at line 354 of file rall2d.h.

double KDL::tanh ( double  a) [inline]

Definition at line 119 of file utility.h.

template<class T , class V , class S >
INLINE Rall2d<T,V,S> KDL::tanh ( const Rall2d< T, V, S > &  arg)

Definition at line 378 of file rall2d.h.

template<class T , class V , class S >
INLINE Rall1d<T,V,S> KDL::tanh ( const Rall1d< T, V, S > &  arg)

Definition at line 424 of file rall1d.h.

template<typename Derived >
void KDL::Twist_to_Eigen ( const KDL::Twist t,
Eigen::MatrixBase< Derived > &  e 
) [inline]

Definition at line 40 of file chainiksolverpos_lma.cpp.


Variable Documentation

const double KDL::deg2rad

the value pi/180

double KDL::epsilon

default precision while comparing with Equal(..,..) functions. Initialized at 0.0000001.

maximal length of a file name

const bool KDL::mhi = true [static]

Definition at line 30 of file rigidbodyinertia.cpp.

const double KDL::PI

the value of pi

const double KDL::rad2deg

the value 180/pi

/note linkage Something fishy about the difference between C++ and C in C++ const values default to INTERNAL linkage, in C they default to EXTERNAL linkage. Here the constants should have EXTERNAL linkage because they, for at least some of them, can be changed by the user. If you want to explicitly declare internal linkage, use "static".

the number of derivatives used in the RN-... objects.



orocos_kdl
Author(s):
autogenerated on Mon Oct 6 2014 03:11:17