Classes | Typedefs | Enumerations | Functions | Variables
KDL Namespace Reference

Classes

class  ArticulatedBodyInertia
 
class  Chain
 
class  ChainDynParam
 
class  ChainFkSolverAcc
 
class  ChainFkSolverPos
 
class  ChainFkSolverPos_recursive
 
class  ChainFkSolverVel
 
class  ChainFkSolverVel_recursive
 
class  ChainIdSolver
 
class  ChainIdSolver_RNE
 
class  ChainIdSolver_Vereshchagin
 
class  ChainIkSolverAcc
 
class  ChainIkSolverPos
 
class  ChainIkSolverPos_LMA
 
class  ChainIkSolverPos_NR
 
class  ChainIkSolverPos_NR_JL
 
class  ChainIkSolverPos_TL
 
class  ChainIkSolverVel
 
class  ChainIkSolverVel_pinv
 
class  ChainIkSolverVel_pinv_givens
 
class  ChainIkSolverVel_pinv_nso
 
class  ChainIkSolverVel_wdls
 
class  ChainJntToJacDotSolver
 
class  ChainJntToJacSolver
 
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
 
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
 
class  Error_Stepsize_To_Small
 
class  Error_Stepsize_Underflow
 
class  Error_To_Many_Steps
 
class  Frame
 
class  Frame2
 
class  FrameAcc
 
class  FrameVel
 
class  Jacobian
 
class  JntArray
 
class  JntArrayAcc
 
class  JntArrayVel
 
class  Joint
 
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
 
class  Rotation
 
class  Rotation2
 
class  RotationAcc
 
class  RotationalInertia
 
class  RotationalInterpolation
 
class  RotationalInterpolation_SingleAxis
 
class  RotationVel
 
class  Segment
 
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
 
class  TreeElement
 
class  TreeFkSolverPos
 
class  TreeFkSolverPos_recursive
 
class  TreeIkSolverPos
 
class  TreeIkSolverPos_NR_JL
 
class  TreeIkSolverPos_Online
 
class  TreeIkSolverVel
 
class  TreeIkSolverVel_wdls
 
class  TreeJntToJacSolver
 
class  Twist
 
class  TwistAcc
 
class  TwistVel
 
class  Vector
 
class  Vector2
 
class  VectorAcc
 
class  VectorVel
 
class  VelocityProfile
 
class  VelocityProfile_Dirac
 
class  VelocityProfile_Rectangular
 
class  VelocityProfile_Spline
 
class  VelocityProfile_Trap
 
class  VelocityProfile_TrapHalf
 
class  Wrench
 

Typedefs

typedef Rall2d< double, double, double > doubleAcc
 
typedef Rall1d< double > doubleVel
 
typedef std::map< std::string, FrameFrames
 
typedef std::map< std::string, JacobianJacobians
 
typedef std::map< std::string, TreeElementSegmentMap
 
typedef TreeElement TreeElementType
 
typedef std::map< std::string, TwistTwists
 
typedef std::vector< WrenchWrenches
 

Enumerations

enum  BasicJointType { RotJoint, TransJoint, Continuous }
 

Functions

void _check_istream (std::istream &is)
 
INLINE Rall1d< T, V, S > abs (const Rall1d< T, V, S > &x)
 
INLINE Rall2d< T, V, S > abs (const Rall2d< T, V, S > &x)
 
double acos (double a)
 
INLINE Rall1d< T, V, S > acos (const Rall1d< T, V, S > &x)
 
INLINE Rall2d< T, V, S > acos (const Rall2d< T, V, S > &arg)
 
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)
 
void Add (const JntArrayVel &src1, const JntArrayVel &src2, JntArrayVel &dest)
 
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)
 
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)
 
IMETHOD Wrench addDelta (const Wrench &a, const Wrench &da, double dt=1)
 
IMETHOD doubleVel addDelta (const doubleVel &a, const doubleVel &da, double dt=1.0)
 
double addDelta (double a, double da, double dt)
 
double asin (double a)
 
INLINE Rall1d< T, V, S > asin (const Rall1d< T, V, S > &x)
 
INLINE Rall2d< T, V, S > asin (const Rall2d< T, V, S > &arg)
 
double atan (double a)
 
INLINE Rall1d< T, V, S > atan (const Rall1d< T, V, S > &x)
 
INLINE Rall2d< T, V, S > atan (const Rall2d< T, V, S > &x)
 
INLINE Rall2d< T, V, S > atan2 (const Rall2d< T, V, S > &y, const Rall2d< T, V, S > &x)
 
double atan2 (double a, double b)
 
INLINE Rall1d< T, V, S > atan2 (const Rall1d< T, V, S > &y, const Rall1d< 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 ()
 
void checkEqual (const T &a, const T &b, double eps)
 
void checkEulerZYX ()
 
void checkFrameOps ()
 
void checkFrameVelOps ()
 
double cos (double a)
 
INLINE Rall1d< T, V, S > cos (const Rall1d< T, V, S > &arg)
 
INLINE Rall2d< T, V, S > cos (const Rall2d< T, V, S > &arg)
 
double cosh (double a)
 
INLINE Rall1d< T, V, S > cosh (const Rall1d< T, V, S > &arg)
 
INLINE Rall2d< T, V, S > cosh (const Rall2d< T, V, S > &arg)
 
Chain d2 ()
 
Chain d6 ()
 
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)
 
IMETHOD Twist diffRelative (const Frame &F_a_b1, const Frame &F_a_b2, double dt=1)
 
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)
 
void Divide (const JntArrayVel &src, const double &factor, JntArrayVel &dest)
 
void Divide (const JntSpaceInertiaMatrix &src, const double &factor, JntSpaceInertiaMatrix &dest)
 
void Divide (const JntArrayVel &src, const doubleVel &factor, JntArrayVel &dest)
 
void Divide (const JntArray &src, const double &factor, JntArray &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)
 
IMETHOD double dot (const Vector &lhs, const Vector &rhs)
 
IMETHOD double dot (const Twist &lhs, const Wrench &rhs)
 
IMETHOD double dot (const Wrench &rhs, const Twist &lhs)
 
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 Rotation2 &a, const Rotation2 &b, double eps=epsilon)
 
bool Equal (const Frame2 &a, const Frame2 &b, double eps=epsilon)
 
bool Equal (const Rotation &a, const Rotation &b, double eps)
 
bool Equal (const JntArrayAcc &src1, const JntArrayAcc &src2, double eps)
 
bool Equal (double a, double b, double eps=epsilon)
 
INLINE bool Equal (const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x, double eps=epsilon)
 
INLINE bool Equal (const Rall2d< T, V, S > &y, const Rall2d< T, V, S > &x, double eps=epsilon)
 
double exp (double a)
 
INLINE Rall1d< T, V, S > exp (const Rall1d< T, V, S > &arg)
 
INLINE Rall2d< T, V, S > exp (const Rall2d< T, V, S > &arg)
 
static void generatePowers (int n, double x, double *powers)
 
INLINE Rall1d< T, V, S > hypot (const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
 
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)
 
void IOTracePop ()
 
void IOTracePopStr (char *buffer, int size)
 
Chain KukaLWR ()
 
Chain KukaLWR_DHnew ()
 
Chain KukaLWRsegment ()
 
double LinComb (double alfa, double a, double beta, double b)
 
INLINE Rall1d< T, V, S > LinComb (S alfa, const Rall1d< T, V, S > &a, const T &beta, const Rall1d< T, V, S > &b)
 
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)
 
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)
 
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)
 
INLINE Rall1d< T, V, S > log (const Rall1d< T, V, S > &arg)
 
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)
 
INLINENorm (const Rall1d< T, V, S > &value)
 
INLINENorm (const Rall2d< T, V, S > &value)
 
IMETHOD bool operator!= (const Frame &a, const Frame &b)
 
IMETHOD bool operator!= (const Vector &a, const Vector &b)
 
IMETHOD bool operator!= (const Twist &a, const Twist &b)
 
IMETHOD bool operator!= (const Wrench &a, const Wrench &b)
 
IMETHOD bool operator!= (const Rotation &a, const Rotation &b)
 
IMETHOD bool operator!= (const Vector2 &a, const Vector2 &b)
 
Wrench operator* (const Twist &lhs, const Wrench &rhs)
 
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)
 
Vector operator* (const Vector &lhs, double rhs)
 
VectorAcc operator* (const VectorAcc &r2, const doubleAcc &r1)
 
ArticulatedBodyInertia operator* (const Rotation &M, const ArticulatedBodyInertia &I)
 
Vector operator* (double lhs, const Vector &rhs)
 
RotationVel operator* (const RotationVel &r1, const RotationVel &r2)
 
RotationVel operator* (const Rotation &r1, const RotationVel &r2)
 
RotationVel operator* (const RotationVel &r1, const Rotation &r2)
 
Vector operator* (const Vector &lhs, const Vector &rhs)
 
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)
 
INLINE Rall1d< T, V, S > operator* (const Rall1d< T, V, S > &lhs, const Rall1d< T, V, S > &rhs)
 
INLINE Rall2d< T, V, S > operator* (const Rall2d< T, V, S > &lhs, const Rall2d< T, V, S > &rhs)
 
Wrench operator* (const Wrench &lhs, double rhs)
 
VectorVel operator* (const VectorVel &r1, const VectorVel &r2)
 
INLINE Rall1d< T, V, S > operator* (S s, const Rall1d< T, V, S > &v)
 
Wrench operator* (double lhs, const Wrench &rhs)
 
VectorVel operator* (const VectorVel &r1, const Vector &r2)
 
VectorVel operator* (const Vector &r1, const VectorVel &r2)
 
INLINE Rall1d< T, V, S > operator* (const Rall1d< T, V, S > &v, S s)
 
VectorAcc operator* (const Rotation &R, const VectorAcc &x)
 
VectorVel operator* (double r1, const VectorVel &r2)
 
INLINE Rall2d< T, V, S > operator* (S s, const Rall2d< T, V, S > &v)
 
VectorVel operator* (const VectorVel &r1, double r2)
 
INLINE Rall2d< T, V, S > operator* (const Rall2d< T, V, S > &v, S s)
 
VectorVel operator* (const doubleVel &r1, const VectorVel &r2)
 
TwistAcc operator* (const TwistAcc &lhs, const doubleAcc &rhs)
 
VectorVel operator* (const VectorVel &r2, const doubleVel &r1)
 
VectorVel operator* (const Rotation &R, const VectorVel &x)
 
Twist operator* (const Twist &lhs, double rhs)
 
TwistVel operator* (const TwistVel &lhs, const doubleVel &rhs)
 
FrameAcc operator* (const FrameAcc &lhs, const FrameAcc &rhs)
 
Twist operator* (double lhs, const Twist &rhs)
 
FrameAcc operator* (const FrameAcc &lhs, const Frame &rhs)
 
FrameAcc operator* (const Frame &lhs, const FrameAcc &rhs)
 
Twist operator* (const Twist &lhs, const Twist &rhs)
 
Frame operator* (const Frame &lhs, const Frame &rhs)
 
TwistVel operator* (const TwistVel &lhs, double rhs)
 
TwistVel operator* (double lhs, const TwistVel &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 doubleAcc &lhs, const TwistAcc &rhs)
 
IMETHOD Vector2 operator* (const Vector2 &lhs, double rhs)
 
IMETHOD Vector2 operator* (double lhs, const Vector2 &rhs)
 
IMETHOD Rotation2 operator* (const Rotation2 &lhs, const Rotation2 &rhs)
 
IMETHOD Frame2 operator* (const Frame2 &lhs, const Frame2 &rhs)
 
VectorVel operator+ (const VectorVel &r1, const VectorVel &r2)
 
TwistAcc operator+ (const TwistAcc &lhs, const TwistAcc &rhs)
 
INLINE Rall2d< T, V, S > operator+ (S s, const Rall2d< T, V, S > &v)
 
IMETHOD Vector operator+ (const Vector &lhs, const Vector &rhs)
 
VectorAcc operator+ (const VectorAcc &r1, const Vector &r2)
 
VectorAcc operator+ (const VectorAcc &r1, const VectorAcc &r2)
 
VectorAcc operator+ (const Vector &r1, const VectorAcc &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 Vector &r2)
 
VectorVel operator+ (const Vector &r1, const VectorVel &r2)
 
INLINE Rall1d< T, V, S > operator+ (const Rall1d< T, V, S > &lhs, const Rall1d< T, V, S > &rhs)
 
INLINE Rall2d< T, V, S > operator+ (const Rall2d< T, V, S > &lhs, const Rall2d< T, V, S > &rhs)
 
Wrench operator+ (const Wrench &lhs, const Wrench &rhs)
 
INLINE Rall1d< T, V, S > operator+ (S s, const Rall1d< T, V, S > &v)
 
INLINE Rall1d< T, V, S > operator+ (const Rall1d< T, V, S > &v, S s)
 
INLINE Rall2d< T, V, S > operator+ (const Rall2d< T, V, S > &v, S s)
 
Twist operator+ (const Twist &lhs, const Twist &rhs)
 
TwistVel operator+ (const TwistVel &lhs, const TwistVel &rhs)
 
IMETHOD Vector2 operator+ (const Vector2 &lhs, const Vector2 &rhs)
 
VectorAcc operator- (const VectorAcc &r)
 
ArticulatedBodyInertia operator- (const ArticulatedBodyInertia &Ia, const ArticulatedBodyInertia &Ib)
 
ArticulatedBodyInertia operator- (const RigidBodyInertia &Ia, const ArticulatedBodyInertia &Ib)
 
IMETHOD Vector operator- (const Vector &lhs, const Vector &rhs)
 
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 VectorVel &r)
 
INLINE Rall1d< T, V, S > operator- (const Rall1d< T, V, S > &lhs, const Rall1d< T, V, S > &rhs)
 
INLINE Rall1d< T, V, S > operator- (const Rall1d< T, V, S > &arg)
 
INLINE Rall2d< T, V, S > operator- (const Rall2d< T, V, S > &arg)
 
Wrench operator- (const Wrench &lhs, const Wrench &rhs)
 
Wrench operator- (const Wrench &arg)
 
INLINE Rall1d< T, V, S > operator- (const Rall1d< T, V, S > &v, S s)
 
INLINE Rall2d< T, V, S > operator- (S s, const Rall2d< T, V, S > &v)
 
INLINE Rall2d< T, V, S > operator- (const Rall2d< T, V, S > &v, S s)
 
Twist operator- (const Twist &lhs, const Twist &rhs)
 
Twist operator- (const Twist &arg)
 
Vector operator- (const Vector &arg)
 
TwistVel operator- (const TwistVel &lhs, const TwistVel &rhs)
 
TwistAcc operator- (const TwistAcc &lhs, const TwistAcc &rhs)
 
TwistAcc operator- (const TwistAcc &arg)
 
IMETHOD Vector2 operator- (const Vector2 &lhs, const Vector2 &rhs)
 
IMETHOD Vector2 operator- (const Vector2 &arg)
 
TwistVel operator- (const TwistVel &arg)
 
INLINE Rall2d< T, V, S > operator- (const Rall2d< T, V, S > &lhs, const Rall2d< T, V, S > &rhs)
 
INLINE Rall1d< T, V, S > operator- (S s, const Rall1d< T, V, S > &v)
 
VectorVel operator- (const Vector &r1, const VectorVel &r2)
 
VectorAcc operator- (const VectorAcc &r1, const Vector &r2)
 
VectorAcc operator- (const VectorAcc &r1, const VectorAcc &r2)
 
VectorAcc operator- (const Vector &r1, const VectorAcc &r2)
 
INLINE Rall2d< T, V, S > operator/ (S s, const Rall2d< T, V, S > &rhs)
 
TwistAcc operator/ (const TwistAcc &lhs, const doubleAcc &rhs)
 
TwistAcc operator/ (const TwistAcc &lhs, double rhs)
 
INLINE Rall2d< T, V, S > operator/ (const Rall2d< T, V, S > &v, S s)
 
INLINE Rall1d< T, V, S > operator/ (const Rall1d< T, V, S > &v, S s)
 
Vector operator/ (const Vector &lhs, double rhs)
 
VectorAcc operator/ (const VectorAcc &r2, const doubleAcc &r1)
 
INLINE Rall2d< T, V, S > operator/ (const Rall2d< T, V, S > &lhs, const Rall2d< T, V, S > &rhs)
 
Wrench operator/ (const Wrench &lhs, double rhs)
 
VectorVel operator/ (const VectorVel &r1, double r2)
 
INLINE Rall1d< T, V, S > operator/ (S s, const Rall1d< T, V, S > &v)
 
INLINE Rall1d< T, V, S > operator/ (const Rall1d< T, V, S > &lhs, const Rall1d< T, V, S > &rhs)
 
Twist operator/ (const Twist &lhs, double rhs)
 
VectorAcc operator/ (const VectorAcc &r1, double r2)
 
VectorVel operator/ (const VectorVel &r2, const doubleVel &r1)
 
TwistVel operator/ (const TwistVel &lhs, double rhs)
 
IMETHOD Vector2 operator/ (const Vector2 &lhs, double rhs)
 
TwistVel operator/ (const TwistVel &lhs, const doubleVel &rhs)
 
std::ostream & operator<< (std::ostream &os, const Twist &v)
 
std::ostream & operator<< (std::ostream &os, const Joint &joint)
 
std::ostream & operator<< (std::ostream &os, const Rall1d< T, V, S > &r)
 
std::ostream & operator<< (std::ostream &os, const Rotation2 &R)
 
std::ostream & operator<< (std::ostream &os, const Jacobian &jac)
 
std::ostream & operator<< (std::ostream &os, const Vector2 &v)
 
std::ostream & operator<< (std::ostream &os, const Rall2d< T, V, S > &r)
 
std::ostream & operator<< (std::ostream &os, const VectorVel &r)
 
std::ostream & operator<< (std::ostream &os, const Segment &segment)
 
std::ostream & operator<< (std::ostream &os, const FrameAcc &r)
 
std::ostream & operator<< (std::ostream &os, const TwistVel &r)
 
std::ostream & operator<< (std::ostream &os, const VectorAcc &r)
 
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 Frame &T)
 
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 Chain &chain)
 
std::ostream & operator<< (std::ostream &os, const Tree &tree)
 
std::ostream & operator<< (std::ostream &os, const Wrench &v)
 
std::ostream & operator<< (std::ostream &os, const Frame2 &T)
 
std::ostream & operator<< (std::ostream &os, const JntSpaceInertiaMatrix &jntspaceinertiamatrix)
 
std::ostream & operator<< (std::ostream &os, SegmentMap::const_iterator root)
 
std::ostream & operator<< (std::ostream &os, const TwistAcc &r)
 
std::ostream & operator<< (std::ostream &os, const Vector &v)
 
std::ostream & operator<< (std::ostream &os, const RotationVel &r)
 
bool operator== (const JntSpaceInertiaMatrix &src1, const JntSpaceInertiaMatrix &src2)
 
bool operator== (const Rotation &a, const Rotation &b)
 
IMETHOD bool operator== (const Vector &a, const Vector &b)
 
IMETHOD bool operator== (const Vector2 &a, const Vector2 &b)
 
IMETHOD bool operator== (const Frame &a, const Frame &b)
 
IMETHOD bool operator== (const Wrench &a, const Wrench &b)
 
IMETHOD bool operator== (const Twist &a, const Twist &b)
 
bool operator== (const JntArray &src1, const JntArray &src2)
 
std::istream & operator>> (std::istream &is, Frame2 &T)
 
std::istream & operator>> (std::istream &is, Frame &T)
 
std::istream & operator>> (std::istream &is, Joint &joint)
 
std::istream & operator>> (std::istream &is, JntArray &array)
 
std::istream & operator>> (std::istream &is, Twist &v)
 
std::istream & operator>> (std::istream &is, Vector2 &v)
 
std::istream & operator>> (std::istream &is, Rotation2 &r)
 
std::istream & operator>> (std::istream &is, Vector &v)
 
std::istream & operator>> (std::istream &is, Chain &chain)
 
std::istream & operator>> (std::istream &is, Wrench &v)
 
std::istream & operator>> (std::istream &is, Tree &tree)
 
std::istream & operator>> (std::istream &is, JntSpaceInertiaMatrix &jntspaceinertiamatrix)
 
std::istream & operator>> (std::istream &is, Jacobian &jac)
 
std::istream & operator>> (std::istream &is, Rotation &r)
 
std::istream & operator>> (std::istream &is, Segment &segment)
 
IMETHOD void posrandom (TwistVel &a)
 
void posrandom (double &a)
 
void posrandom (Stiffness &F)
 
IMETHOD void posrandom (Wrench &a)
 
IMETHOD void posrandom (Frame &F)
 
IMETHOD void posrandom (Vector &a)
 
IMETHOD void posrandom (Rotation &R)
 
IMETHOD void posrandom (FrameVel &F)
 
IMETHOD void posrandom (doubleVel &F)
 
IMETHOD void posrandom (Twist &a)
 
void posrandom (Jacobian< T > &rv)
 
IMETHOD void posrandom (RotationVel &R)
 
IMETHOD void posrandom (VectorVel &a)
 
double pow (double a, double b)
 
INLINE Rall1d< T, V, S > pow (const Rall1d< T, V, S > &arg, double m)
 
INLINE Rall2d< T, V, S > pow (const Rall2d< T, V, S > &arg, double m)
 
Chain Puma560 ()
 
double PYTHAG (double a, double b)
 
IMETHOD void random (Twist &a)
 
IMETHOD void random (FrameVel &F)
 
IMETHOD void random (doubleVel &F)
 
IMETHOD void random (TwistVel &a)
 
IMETHOD void random (Vector &a)
 
IMETHOD void random (RotationVel &R)
 
IMETHOD void random (Rotation &R)
 
IMETHOD void random (Frame &F)
 
IMETHOD void random (Wrench &a)
 
void random (Jacobian< T > &rv)
 
IMETHOD void random (VectorVel &a)
 
void random (Stiffness &F)
 
void random (double &a)
 
IMETHOD Rotation Rot (const Vector &axis_a_b)
 
INLINE void SetToIdentity (Rall2d< T, V, S > &value)
 
void SetToIdentity (double &arg)
 
INLINE void SetToIdentity (Rall1d< T, V, S > &value)
 
void SetToZero (VectorVel &v)
 
void SetToZero (TwistVel &v)
 
IMETHOD void SetToZero (Vector2 &v)
 
IMETHOD void SetToZero (Twist &v)
 
INLINE void SetToZero (Rall2d< T, V, S > &value)
 
void SetToZero (JntArrayVel &array)
 
IMETHOD void SetToZero (Wrench &v)
 
IMETHOD void SetToZero (Vector &v)
 
void SetToZero (JntArrayAcc &array)
 
void SetToZero (JntArray &array)
 
INLINE void SetToZero (Rall1d< T, V, S > &value)
 
void SetToZero (JntSpaceInertiaMatrix &mat)
 
void SetToZero (double &arg)
 
void SetToZero (Jacobian &jac)
 
double sign (double arg)
 
double SIGN (double a, double b)
 
INLINE Rall1d< T, V, S > sin (const Rall1d< T, V, S > &arg)
 
double sin (double a)
 
INLINE Rall2d< T, V, S > sin (const Rall2d< T, V, S > &arg)
 
double sinh (double a)
 
INLINE Rall1d< T, V, S > sinh (const Rall1d< T, V, S > &arg)
 
INLINE Rall2d< T, V, S > sinh (const Rall2d< T, V, S > &arg)
 
INLINE Rall1d< T, V, S > sqr (const Rall1d< T, V, S > &arg)
 
INLINE Rall2d< T, V, S > sqr (const Rall2d< T, V, S > &arg)
 
double sqr (double arg)
 
double sqrt (double a)
 
INLINE Rall2d< T, V, S > sqrt (const Rall2d< T, V, S > &arg)
 
INLINE Rall1d< T, V, S > sqrt (const Rall1d< T, V, S > &arg)
 
void Subtract (const JntArray &src1, const JntArray &src2, JntArray &dest)
 
void Subtract (const JntArrayAcc &src1, const JntArrayVel &src2, JntArrayAcc &dest)
 
void Subtract (const JntArrayVel &src1, const JntArray &src2, JntArrayVel &dest)
 
void Subtract (const JntSpaceInertiaMatrix &src1, const JntSpaceInertiaMatrix &src2, JntSpaceInertiaMatrix &dest)
 
void Subtract (const JntArrayAcc &src1, const JntArray &src2, JntArrayAcc &dest)
 
void Subtract (const JntArrayAcc &src1, const JntArrayAcc &src2, JntArrayAcc &dest)
 
void Subtract (const JntArrayVel &src1, const JntArrayVel &src2, JntArrayVel &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 threshold, bool toggle)
 
INLINE Rall2d< T, V, S > tan (const Rall2d< T, V, S > &arg)
 
double tan (double a)
 
INLINE Rall1d< T, V, S > tan (const Rall1d< T, V, S > &arg)
 
INLINE Rall1d< T, V, S > tanh (const Rall1d< T, V, S > &arg)
 
INLINE Rall2d< T, V, S > tanh (const Rall2d< T, V, S > &arg)
 
double tanh (double a)
 
void Twist_to_Eigen (const KDL::Twist &t, Eigen::MatrixBase< Derived > &e)
 

Variables

const double deg2rad
 
double epsilon
 
static const double L0
 
static const double L1
 
static const double L2
 
static const double L3
 
static const double L4
 
static const double L5
 
int MAXLENFILENAME
 
static const bool mhi
 
const double PI
 
const double rad2deg
 
int STREAMBUFFERSIZE
 
int VSIZE
 

Enumeration Type Documentation

Enumerator
RotJoint 
TransJoint 
Continuous 

Definition at line 46 of file kdl_tl.hpp.

Function Documentation

IMETHOD Twist KDL::diffRelative ( const Frame F_a_b1,
const Frame F_a_b2,
double  dt = 1 
)

determines the rotation axis necessary to rotate from frame b1 to the orientation of 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. The result is w.r.t. frame b1.

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 real Twist!
In contrast to standard KDL diff methods, the result of diffRelative is w.r.t. frame b1 instead of frame a.

Definition at line 118 of file kdl_tl.hpp.



trac_ik_lib
Author(s): Patrick Beeson, Barrett Ames
autogenerated on Tue Apr 23 2019 02:39:13