Namespaces | |
Corba | |
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< Wrench > | Wrenches |
typedef std::map< std::string, Wrench > | WrenchMap |
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) |
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) |
Frame | framerv (const Rotation &r, const Vector &v) |
Frame | framevr (const Vector &v, const Rotation &r) |
static void | generatePowers (int n, double x, double *powers) |
template<class KDLType , int size> | |
double & | get_container_item (KDLType &cont, int index) |
template<class KDLType , int size> | |
double | get_container_item_copy (const KDLType &cont, int index) |
double & | get_item (JntArray &v, int index) |
double | get_item_copy (const JntArray &v, int index) |
int | get_size (const JntArray &v) |
void | GetQuaternion (const Rotation &rot, double &x, double &y, double &z, double &w) |
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) |
Rotation | Inverse (const Rotation &rot) |
Frame | Inverse (const Frame &f) |
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 () |
int | ldl_solver_eigen (const Eigen::MatrixXd &A, const Eigen::VectorXd &v, Eigen::MatrixXd &L, Eigen::VectorXd &D, Eigen::VectorXd &vtmp, Eigen::VectorXd &q) |
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) |
void | loadChainTypes () |
void | loadFrameTypes () |
void | loadJacobianTypes () |
void | loadJntArrayTypes () |
void | loadJointTypes () |
void | loadRotationTypes () |
void | loadSegmentTypes () |
void | loadTwistTypes () |
void | loadVectorTypes () |
void | loadWrenchTypes () |
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) |
INLINE S | Norm (const Rall1d< T, V, S > &value) |
INLINE S | Norm (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) |
TwistAcc | operator* (const doubleAcc &lhs, const TwistAcc &rhs) |
TwistVel | operator* (const TwistVel &lhs, double rhs) |
IMETHOD Vector2 | operator* (const Vector2 &lhs, double rhs) |
TwistVel | operator* (const doubleVel &lhs, const TwistVel &rhs) |
FrameVel | operator* (const FrameVel &lhs, const FrameVel &rhs) |
TwistVel | operator* (const TwistVel &lhs, const doubleVel &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) |
TwistVel | operator* (double lhs, const TwistVel &rhs) |
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) |
IMETHOD Vector2 | operator* (double lhs, const Vector2 &rhs) |
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) |
Frame | operator* (const Frame &lhs, const Frame &rhs) |
VectorVel | operator* (const VectorVel &r1, const VectorVel &r2) |
Wrench | operator* (double lhs, const Wrench &rhs) |
INLINE Rall1d< T, V, S > | operator* (S s, const Rall1d< T, V, S > &v) |
VectorVel | operator* (const VectorVel &r1, const Vector &r2) |
INLINE Rall1d< T, V, S > | operator* (const Rall1d< T, V, S > &v, S s) |
VectorVel | operator* (const Vector &r1, const VectorVel &r2) |
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) |
VectorVel | operator* (const VectorVel &r2, const doubleVel &r1) |
VectorVel | operator* (const Rotation &R, const VectorVel &x) |
Twist | operator* (const Twist &lhs, double rhs) |
FrameAcc | operator* (const FrameAcc &lhs, const FrameAcc &rhs) |
Wrench | operator* (const Twist &lhs, const Wrench &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) |
TwistAcc | operator* (double lhs, const TwistAcc &rhs) |
TwistAcc | operator* (const TwistAcc &lhs, const doubleAcc &rhs) |
IMETHOD Rotation2 | operator* (const Rotation2 &lhs, const Rotation2 &rhs) |
IMETHOD Frame2 | operator* (const Frame2 &lhs, const Frame2 &rhs) |
TwistAcc | operator* (const TwistAcc &lhs, double rhs) |
TwistVel | operator+ (const TwistVel &lhs, const TwistVel &rhs) |
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 > &v, S s) |
ArticulatedBodyInertia | operator+ (const ArticulatedBodyInertia &Ia, const RigidBodyInertia &Ib) |
RotationalInertia | operator+ (const RotationalInertia &Ia, const RotationalInertia &Ib) |
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) |
IMETHOD Vector | operator+ (const Vector &lhs, const Vector &rhs) |
ArticulatedBodyInertia | operator+ (const RigidBodyInertia &Ia, const ArticulatedBodyInertia &Ib) |
Stiffness | operator+ (const Stiffness &s1, const Stiffness &s2) |
VectorVel | operator+ (const VectorVel &r1, const VectorVel &r2) |
VectorVel | operator+ (const VectorVel &r1, const Vector &r2) |
VectorVel | operator+ (const Vector &r1, const VectorVel &r2) |
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 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) |
TwistAcc | operator+ (const TwistAcc &lhs, const TwistAcc &rhs) |
IMETHOD Vector2 | operator+ (const Vector2 &lhs, const Vector2 &rhs) |
INLINE Rall2d< T, V, S > | operator- (const Rall2d< T, V, S > &v, S s) |
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) |
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 Vector &r1, const VectorVel &r2) |
INLINE Rall1d< T, V, S > | operator- (const Rall1d< T, V, S > &lhs, const Rall1d< T, V, S > &rhs) |
VectorVel | operator- (const VectorVel &r) |
INLINE Rall2d< T, V, S > | operator- (const Rall2d< T, V, S > &lhs, const Rall2d< T, V, S > &rhs) |
INLINE Rall2d< T, V, S > | operator- (const Rall2d< T, V, S > &arg) |
Wrench | operator- (const Wrench &lhs, const Wrench &rhs) |
TwistVel | operator- (const TwistVel &lhs, const TwistVel &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- (S s, const Rall2d< T, V, S > &v) |
Twist | operator- (const Twist &lhs, const Twist &rhs) |
Twist | operator- (const Twist &arg) |
Vector | operator- (const Vector &arg) |
TwistVel | operator- (const TwistVel &arg) |
TwistAcc | operator- (const TwistAcc &lhs, const TwistAcc &rhs) |
TwistAcc | operator- (const TwistAcc &arg) |
IMETHOD Vector2 | operator- (const Vector2 &arg) |
IMETHOD Vector2 | operator- (const Vector2 &lhs, const Vector2 &rhs) |
Wrench | operator- (const Wrench &arg) |
INLINE Rall1d< T, V, S > | operator- (const Rall1d< T, V, S > &arg) |
VectorVel | operator- (const VectorVel &r1, const Vector &r2) |
VectorAcc | operator- (const Vector &r1, const VectorAcc &r2) |
VectorAcc | operator- (const VectorAcc &r1, const VectorAcc &r2) |
Twist | operator/ (const Twist &lhs, double rhs) |
INLINE Rall2d< T, V, S > | operator/ (const Rall2d< T, V, S > &v, S s) |
TwistAcc | operator/ (const TwistAcc &lhs, double rhs) |
Vector | operator/ (const Vector &lhs, double rhs) |
VectorAcc | operator/ (const VectorAcc &r1, double 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) |
INLINE Rall2d< T, V, S > | operator/ (S s, const Rall2d< T, V, S > &rhs) |
VectorVel | operator/ (const VectorVel &r2, const doubleVel &r1) |
INLINE Rall1d< T, V, S > | operator/ (const Rall1d< T, V, S > &v, S s) |
INLINE Rall1d< T, V, S > | operator/ (S s, const Rall1d< T, V, S > &v) |
TwistVel | operator/ (const TwistVel &lhs, double rhs) |
VectorVel | operator/ (const VectorVel &r1, double r2) |
VectorAcc | operator/ (const VectorAcc &r2, const doubleAcc &r1) |
IMETHOD Vector2 | operator/ (const Vector2 &lhs, double rhs) |
TwistVel | operator/ (const TwistVel &lhs, const doubleVel &rhs) |
TwistAcc | operator/ (const TwistAcc &lhs, const doubleAcc &rhs) |
std::ostream & | operator<< (std::ostream &os, const TwistVel &r) |
std::ostream & | operator<< (std::ostream &os, const RotationAcc &r) |
std::ostream & | operator<< (std::ostream &os, const Wrench &v) |
std::ostream & | operator<< (std::ostream &os, const Tree &tree) |
std::ostream & | operator<< (std::ostream &os, const Segment &segment) |
std::ostream & | operator<< (std::ostream &os, const Vector2 &v) |
std::ostream & | operator<< (std::ostream &os, const JntArray &array) |
std::ostream & | operator<< (std::ostream &os, const FrameVel &r) |
std::ostream & | operator<< (std::ostream &os, const Rall1d< T, V, S > &r) |
std::ostream & | operator<< (std::ostream &os, const Rall2d< T, V, S > &r) |
std::ostream & | operator<< (std::ostream &os, const RotationVel &r) |
std::ostream & | operator<< (std::ostream &os, const Vector &v) |
std::ostream & | operator<< (std::ostream &os, const Chain &chain) |
std::ostream & | operator<< (std::ostream &os, const TwistAcc &r) |
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 JntSpaceInertiaMatrix &jntspaceinertiamatrix) |
std::ostream & | operator<< (std::ostream &os, const Frame2 &T) |
std::ostream & | operator<< (std::ostream &os, const FrameAcc &r) |
std::ostream & | operator<< (std::ostream &os, const Twist &v) |
std::ostream & | operator<< (std::ostream &os, const Jacobian &jac) |
std::ostream & | operator<< (std::ostream &os, const Rotation2 &R) |
std::ostream & | operator<< (std::ostream &os, const VectorVel &r) |
std::ostream & | operator<< (std::ostream &os, const Joint &joint) |
std::ostream & | operator<< (std::ostream &os, const VectorAcc &r) |
std::ostream & | operator<< (std::ostream &os, const Frame &T) |
IMETHOD bool | operator== (const Frame &a, const Frame &b) |
IMETHOD bool | operator== (const Vector2 &a, const Vector2 &b) |
bool | operator== (const JntArray &src1, const JntArray &src2) |
IMETHOD bool | operator== (const Twist &a, const Twist &b) |
IMETHOD bool | operator== (const Wrench &a, const Wrench &b) |
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) |
std::istream & | operator>> (std::istream &is, Joint &joint) |
std::istream & | operator>> (std::istream &is, Segment &segment) |
std::istream & | operator>> (std::istream &is, Tree &tree) |
std::istream & | operator>> (std::istream &is, Vector &v) |
std::istream & | operator>> (std::istream &is, Wrench &v) |
std::istream & | operator>> (std::istream &is, Frame &T) |
std::istream & | operator>> (std::istream &is, Chain &chain) |
std::istream & | operator>> (std::istream &is, Twist &v) |
std::istream & | operator>> (std::istream &is, Jacobian &jac) |
std::istream & | operator>> (std::istream &is, JntSpaceInertiaMatrix &jntspaceinertiamatrix) |
std::istream & | operator>> (std::istream &is, Rotation2 &r) |
std::istream & | operator>> (std::istream &is, Frame2 &T) |
std::istream & | operator>> (std::istream &is, Rotation &r) |
std::istream & | operator>> (std::istream &is, Vector2 &v) |
std::istream & | operator>> (std::istream &is, JntArray &array) |
IMETHOD void | posrandom (Wrench &a) |
void | posrandom (Stiffness &F) |
void | posrandom (Jacobian< T > &rv) |
IMETHOD void | posrandom (doubleVel &F) |
IMETHOD void | posrandom (VectorVel &a) |
IMETHOD void | posrandom (Vector &a) |
IMETHOD void | posrandom (Twist &a) |
IMETHOD void | posrandom (TwistVel &a) |
IMETHOD void | posrandom (RotationVel &R) |
void | posrandom (double &a) |
IMETHOD void | posrandom (Frame &F) |
IMETHOD void | posrandom (Rotation &R) |
IMETHOD void | posrandom (FrameVel &F) |
INLINE Rall2d< T, V, S > | pow (const Rall2d< T, V, S > &arg, double m) |
double | pow (double a, double b) |
INLINE Rall1d< T, V, S > | pow (const Rall1d< T, V, S > &arg, double m) |
Chain | Puma560 () |
double | PYTHAG (double a, double b) |
IMETHOD void | random (Rotation &R) |
IMETHOD void | random (Frame &F) |
IMETHOD void | random (Twist &a) |
IMETHOD void | random (Vector &a) |
IMETHOD void | random (RotationVel &R) |
void | random (double &a) |
void | random (Stiffness &F) |
IMETHOD void | random (Wrench &a) |
void | random (Jacobian< T > &rv) |
IMETHOD void | random (VectorVel &a) |
IMETHOD void | random (TwistVel &a) |
IMETHOD void | random (FrameVel &F) |
IMETHOD void | random (doubleVel &F) |
IMETHOD Rotation | Rot (const Vector &axis_a_b) |
Rotation | rotationAngleAxis (const Vector &axis, double angle) |
INLINE void | SetToIdentity (Rall2d< T, V, S > &value) |
INLINE void | SetToIdentity (Rall1d< T, V, S > &value) |
void | SetToIdentity (double &arg) |
IMETHOD void | SetToZero (Vector &v) |
IMETHOD void | SetToZero (Twist &v) |
IMETHOD void | SetToZero (Wrench &v) |
IMETHOD void | SetToZero (Vector2 &v) |
void | SetToZero (TwistVel &v) |
void | SetToZero (JntSpaceInertiaMatrix &mat) |
INLINE void | SetToZero (Rall1d< T, V, S > &value) |
void | SetToZero (JntArray &array) |
void | SetToZero (JntArrayVel &array) |
INLINE void | SetToZero (Rall2d< T, V, S > &value) |
void | SetToZero (JntArrayAcc &array) |
void | SetToZero (Jacobian &jac) |
void | SetToZero (double &arg) |
void | SetToZero (VectorVel &v) |
double | sign (double arg) |
double | SIGN (double a, double b) |
INLINE Rall1d< T, V, S > | sin (const Rall1d< T, V, S > &arg) |
INLINE Rall2d< T, V, S > | sin (const Rall2d< T, V, S > &arg) |
double | sin (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) |
double | sinh (double a) |
INLINE Rall1d< T, V, S > | sqr (const Rall1d< T, V, S > &arg) |
double | sqr (double arg) |
INLINE Rall2d< T, V, S > | sqr (const Rall2d< T, V, S > &arg) |
double | sqrt (double a) |
INLINE Rall1d< T, V, S > | sqrt (const Rall1d< T, V, S > &arg) |
INLINE Rall2d< T, V, S > | sqrt (const Rall2d< T, V, S > &arg) |
void | Subtract (const JntArray &src1, const JntArray &src2, JntArray &dest) |
void | Subtract (const JntArrayAcc &src1, const JntArray &src2, JntArrayAcc &dest) |
void | Subtract (const JntSpaceInertiaMatrix &src1, const JntSpaceInertiaMatrix &src2, JntSpaceInertiaMatrix &dest) |
void | Subtract (const JntArrayVel &src1, const JntArray &src2, JntArrayVel &dest) |
void | Subtract (const JntArrayAcc &src1, const JntArrayAcc &src2, JntArrayAcc &dest) |
void | Subtract (const JntArrayAcc &src1, const JntArrayVel &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) |
void | swap (scoped_ptr< T > &, scoped_ptr< T > &) |
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) |
double | tanh (double a) |
INLINE Rall1d< T, V, S > | tanh (const Rall1d< T, V, S > &arg) |
INLINE Rall2d< T, V, S > | tanh (const Rall2d< T, V, S > &arg) |
void | Twist_to_Eigen (const KDL::Twist &t, Eigen::MatrixBase< Derived > &e) |
Twist | twistvw (const Vector &trans, const Vector &rot) |
Vector | vectorxyz (double a, double b, double c) |
Wrench | wrenchft (const Vector &force, const Vector &torque) |
Variables | |
const double | deg2rad |
double | epsilon |
KDLTypekitPlugin | KDLTypekit |
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 |
Definition at line 8 of file kdlTypekitConstructors.cpp.
Definition at line 4 of file kdlTypekitConstructors.cpp.
double& KDL::get_container_item | ( | KDLType & | cont, |
int | index | ||
) |
Helper functions. Returns a reference to one item in an KDL container.
cont | The container to access |
index | The item to reference |
Definition at line 86 of file kdlTypekit.hpp.
double KDL::get_container_item_copy | ( | const KDLType & | cont, |
int | index | ||
) |
Returns a copy to one item in an STL container.
cont | The container to access |
index | The item to extract from the sequence |
Definition at line 101 of file kdlTypekit.hpp.
double& KDL::get_item | ( | JntArray & | v, |
int | index | ||
) |
Definition at line 20 of file kdlTypekitJntArray.cpp.
double KDL::get_item_copy | ( | const JntArray & | v, |
int | index | ||
) |
Definition at line 27 of file kdlTypekitJntArray.cpp.
int KDL::get_size | ( | const JntArray & | v | ) |
Definition at line 35 of file kdlTypekitJntArray.cpp.
void KDL::GetQuaternion | ( | const Rotation & | rot, |
double & | x, | ||
double & | y, | ||
double & | z, | ||
double & | w | ||
) |
Definition at line 14 of file kdlTypekitOperators.cpp.
Definition at line 6 of file kdlTypekitOperators.cpp.
Definition at line 10 of file kdlTypekitOperators.cpp.
void KDL::loadChainTypes | ( | ) |
Definition at line 18 of file kdlTypekitChain.cpp.
void KDL::loadFrameTypes | ( | ) |
Definition at line 28 of file kdlTypekitFrame.cpp.
void KDL::loadJacobianTypes | ( | ) |
Definition at line 18 of file kdlTypekitJacobian.cpp.
void KDL::loadJntArrayTypes | ( | ) |
Definition at line 184 of file kdlTypekitJntArray.cpp.
void KDL::loadJointTypes | ( | ) |
Definition at line 18 of file kdlTypekitJoint.cpp.
void KDL::loadRotationTypes | ( | ) |
Definition at line 28 of file kdlTypekitRotation.cpp.
void KDL::loadSegmentTypes | ( | ) |
Definition at line 18 of file kdlTypekitSegment.cpp.
void KDL::loadTwistTypes | ( | ) |
Definition at line 28 of file kdlTypekitTwist.cpp.
void KDL::loadVectorTypes | ( | ) |
Definition at line 28 of file kdlTypekitVector.cpp.
void KDL::loadWrenchTypes | ( | ) |
Definition at line 28 of file kdlTypekitWrench.cpp.
Definition at line 172 of file kdlTypekitConstructors.cpp.
Definition at line 19 of file kdlTypekitConstructors.cpp.
Vector KDL::vectorxyz | ( | double | a, |
double | b, | ||
double | c | ||
) |
Definition at line 24 of file kdlTypekitConstructors.cpp.
Definition at line 14 of file kdlTypekitConstructors.cpp.
KDLTypekitPlugin KDL::KDLTypekit |
The single global instance of the KDL Typekit.
Definition at line 48 of file kdlTypekit.cpp.