Classes | |
class | ArticulatedBodyInertia |
6D Inertia of a articulated body More... | |
class | Chain |
This class encapsulates a serial kinematic interconnection structure. It is built out of segments. More... | |
class | ChainDynParam |
class | ChainFdSolver |
This abstract class encapsulates the inverse dynamics solver for a KDL::Chain. More... | |
class | ChainFdSolver_RNE |
Recursive newton euler forward dynamics solver. More... | |
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 | ChainHdSolver_Vereshchagin |
Abstract: Acceleration constrained hybrid dynamics calculations for a chain, based on Vereshchagin 1989. This class creates an instance of the hybrid dynamics solver. The solver analytically calculates the joint space constraint torques and acceleration in a chain when a constraint force(s) is applied to the chain's end-effector (task space / cartesian space). In the robotics literature, this algorithm is also known under the following names: Acceleration Constrained Hybrid Dynamics (ACHD) and Popov-Vereshchagin solver. More... | |
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 |
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 | ChainJntToJacDotSolver |
Computes the Jacobian time derivative (Jdot) by calculating the partial derivatives regarding to a joint angle, in the Hybrid, Body-fixed or Inertial representation. More... | |
class | ChainJntToJacSolver |
Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers. 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 occurred 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 | JntArray |
This class represents an fixed size array containing joint values of a KDL::Chain. More... | |
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 | scoped_ptr |
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 built 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 | TreeIdSolver |
This abstract class encapsulates the inverse dynamics solver for a KDL::Tree. More... | |
class | TreeIdSolver_RNE |
Recursive newton euler inverse dynamics solver for kinematic trees. More... | |
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< Wrench > | Wrenches |
typedef std::map< std::string, Wrench > | WrenchMap |
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. More... | |
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. More... | |
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. More... | |
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) |
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 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) |
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) |
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. More... | |
void | IOTracePop () |
pops a description of the IO-stack More... | |
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) |
Solves the system of equations Aq = v for q via LDL decomposition, where A is a square positive definite matrix. More... | |
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 > | |
INLINE S | Norm (const Rall1d< T, V, S > &value) |
template<class T , class V , class S > | |
INLINE S | Norm (const Rall2d< T, V, S > &value) |
bool | operator!= (const FrameVel &r1, const FrameVel &r2) |
bool | operator!= (const Frame &r1, const FrameVel &r2) |
bool | operator!= (const FrameVel &r1, const Frame &r2) |
bool | operator!= (const VectorVel &r1, const VectorVel &r2) |
bool | operator!= (const Vector &r1, const VectorVel &r2) |
bool | operator!= (const VectorVel &r1, const Vector &r2) |
bool | operator!= (const RotationVel &r1, const RotationVel &r2) |
bool | operator!= (const Rotation &r1, const RotationVel &r2) |
bool | operator!= (const RotationVel &r1, const Rotation &r2) |
bool | operator!= (const TwistVel &a, const TwistVel &b) |
bool | operator!= (const Twist &r1, const TwistVel &r2) |
template<class T , class V , class S > | |
INLINE bool | operator!= (const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x) |
bool | operator!= (const TwistVel &r1, const Twist &r2) |
template<class T , class V , class S > | |
INLINE bool | operator!= (const Rall2d< T, V, S > &y, const Rall2d< T, V, S > &x) |
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) |
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) |
Vector | operator* (const Vector &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) |
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) |
Wrench | operator* (const Wrench &lhs, double rhs) |
template<class T , class V , class S > | |
INLINE Rall1d< T, V, S > | operator* (S s, const Rall1d< T, V, S > &v) |
Wrench | operator* (double lhs, const Wrench &rhs) |
template<class T , class V , class S > | |
INLINE Rall1d< T, V, S > | operator* (const Rall1d< T, V, S > &v, S s) |
VectorAcc | operator* (const Rotation &R, const VectorAcc &x) |
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) |
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* (double r1, const VectorVel &r2) |
VectorVel | operator* (const VectorVel &r1, double r2) |
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) |
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) |
Wrench | operator* (const Twist &lhs, const Wrench &rhs) |
Frame | operator* (const Frame &lhs, const Frame &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) |
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) |
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) |
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) |
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) |
ArticulatedBodyInertia | operator+ (const ArticulatedBodyInertia &Ia, const RigidBodyInertia &Ib) |
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) |
VectorVel | operator+ (const VectorVel &r1, const Vector &r2) |
Wrench | operator+ (const Wrench &lhs, const Wrench &rhs) |
template<class T , class V , class S > | |
INLINE Rall1d< T, V, S > | operator+ (S s, const Rall1d< T, V, S > &v) |
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 > &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) |
Twist | operator+ (const Twist &lhs, const Twist &rhs) |
TwistAcc | operator+ (const TwistAcc &lhs, const TwistAcc &rhs) |
TwistVel | operator+ (const TwistVel &lhs, const TwistVel &rhs) |
IMETHOD Vector2 | operator+ (const Vector2 &lhs, const Vector2 &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) |
IMETHOD Vector | operator- (const Vector &lhs, const Vector &rhs) |
ArticulatedBodyInertia | operator- (const ArticulatedBodyInertia &Ia, const RigidBodyInertia &Ib) |
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) |
VectorVel | operator- (const VectorVel &r1, const VectorVel &r2) |
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) |
VectorVel | operator- (const VectorVel &r1, const Vector &r2) |
Wrench | operator- (const Wrench &lhs, const Wrench &rhs) |
VectorVel | operator- (const Vector &r1, const VectorVel &r2) |
Wrench | operator- (const Wrench &arg) |
VectorVel | operator- (const VectorVel &r) |
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) |
Twist | operator- (const Twist &lhs, const Twist &rhs) |
Twist | operator- (const Twist &arg) |
Vector | operator- (const Vector &arg) |
TwistAcc | operator- (const TwistAcc &lhs, const TwistAcc &rhs) |
TwistAcc | operator- (const TwistAcc &arg) |
TwistVel | operator- (const TwistVel &lhs, const TwistVel &rhs) |
TwistVel | operator- (const TwistVel &arg) |
IMETHOD Vector2 | operator- (const Vector2 &lhs, const Vector2 &rhs) |
IMETHOD Vector2 | operator- (const Vector2 &arg) |
Vector | operator/ (const Vector &lhs, double rhs) |
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) |
Wrench | operator/ (const Wrench &lhs, double 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 > &rhs) |
template<class T , class V , class S > | |
INLINE Rall2d< T, V, S > | operator/ (const Rall2d< T, V, S > &v, S s) |
VectorVel | operator/ (const VectorVel &r1, double r2) |
VectorVel | operator/ (const VectorVel &r2, const doubleVel &r1) |
Twist | operator/ (const Twist &lhs, double rhs) |
TwistAcc | operator/ (const TwistAcc &lhs, double rhs) |
TwistAcc | operator/ (const TwistAcc &lhs, const doubleAcc &rhs) |
TwistVel | operator/ (const TwistVel &lhs, double rhs) |
TwistVel | operator/ (const TwistVel &lhs, const doubleVel &rhs) |
IMETHOD Vector2 | operator/ (const Vector2 &lhs, double 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) |
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 VectorVel &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 TwistVel &r) |
std::ostream & | operator<< (std::ostream &os, const Chain &chain) |
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 FrameVel &r1, const FrameVel &r2) |
bool | operator== (const Frame &r1, const FrameVel &r2) |
bool | operator== (const FrameVel &r1, const Frame &r2) |
bool | operator== (const JntSpaceInertiaMatrix &src1, const JntSpaceInertiaMatrix &src2) |
bool | operator== (const JntArray &src1, const JntArray &src2) |
bool | operator== (const VectorVel &r1, const VectorVel &r2) |
bool | operator== (const Vector &r1, const VectorVel &r2) |
bool | operator== (const VectorVel &r1, const Vector &r2) |
bool | operator== (const RotationVel &r1, const RotationVel &r2) |
bool | operator== (const Rotation &r1, const RotationVel &r2) |
bool | operator== (const Rotation &a, const Rotation &b) |
bool | operator== (const RotationVel &r1, const Rotation &r2) |
bool | operator== (const TwistVel &a, const TwistVel &b) |
bool | operator== (const Twist &a, const TwistVel &b) |
template<class T , class V , class S > | |
INLINE bool | operator== (const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x) |
bool | operator== (const TwistVel &r1, const Twist &r2) |
template<class T , class V , class S > | |
INLINE bool | operator== (const Rall2d< T, V, S > &y, const Rall2d< T, V, S > &x) |
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 Vector2 &a, const Vector2 &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) |
IMETHOD void | posrandom (Vector &a) |
IMETHOD void | posrandom (Twist &a) |
IMETHOD void | posrandom (Wrench &a) |
IMETHOD void | posrandom (Rotation &R) |
IMETHOD void | posrandom (Frame &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) |
IMETHOD void | random (Vector &a) |
addDelta operator for displacement rotational velocity. More... | |
IMETHOD void | random (Twist &a) |
IMETHOD void | random (Wrench &a) |
IMETHOD void | random (Rotation &R) |
IMETHOD void | random (Frame &F) |
IMETHOD Rotation | Rot (const Vector &axis_a_b) |
void | SetToIdentity (double &arg) |
to uniformly set double, RNDouble,Vector,... objects to the identity element in template-classes More... | |
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 More... | |
void | SetToZero (VectorVel &v) |
template<class T , class V , class S > | |
INLINE void | SetToZero (Rall1d< T, V, S > &value) |
template<class T , class V , class S > | |
INLINE void | SetToZero (Rall2d< T, V, S > &value) |
void | SetToZero (TwistVel &v) |
IMETHOD void | SetToZero (Vector &v) |
IMETHOD void | SetToZero (Twist &v) |
IMETHOD void | SetToZero (Wrench &v) |
IMETHOD void | SetToZero (Vector2 &v) |
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 Eigen::MatrixXd &A, Eigen::MatrixXd &U, Eigen::VectorXd &S, Eigen::MatrixXd &V, Eigen::MatrixXd &B, Eigen::VectorXd &tempi, double threshold, bool toggle) |
template<typename T > | |
void | swap (scoped_ptr< T > &, scoped_ptr< T > &) |
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) |
std::string | tree2str (const SegmentMap::const_iterator it, const std::string &separator, const std::string &preamble, unsigned int level) |
std::string | tree2str (const Tree &tree, const std::string &separator, const std::string &preamble) |
template<typename Derived > | |
void | Twist_to_Eigen (const KDL::Twist &t, Eigen::MatrixBase< Derived > &e) |
Variables | |
const double | deg2rad |
the value pi/180 More... | |
double | epsilon |
default precision while comparing with Equal(..,..) functions. Initialized at 0.0000001. More... | |
static const double | L0 = 1.0 |
static const double | L1 = 0.5 |
static const double | L2 = 0.4 |
static const double | L3 = 0 |
static const double | L4 = 0 |
static const double | L5 = 0 |
int | MAXLENFILENAME |
maximal length of a file name More... | |
static const bool | mhi =true |
const double | PI |
the value of pi More... | |
const double | PI_2 |
the value of pi/2 More... | |
const double | PI_4 |
the value of pi/4 More... | |
const double | rad2deg |
the value 180/pi More... | |
int | STREAMBUFFERSIZE |
int | VSIZE |
the number of derivatives used in the RN-... objects. More... | |
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 |
typedef TreeElement KDL::TreeElementType |
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 34 of file chainfdsolver.hpp.
typedef std::map<std::string,Wrench> KDL::WrenchMap |
Definition at line 33 of file treeidsolver.hpp.
void KDL::_check_istream | ( | std::istream & | is | ) |
checks validity of basic io of is
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.
Function to add two joint arrays, all the arguments must have the same size: A + B = C. This function is aliasing-safe, A or B can be the same array as C.
src1 | A |
src2 | B |
dest | C |
Definition at line 82 of file jntarray.cpp.
Definition at line 42 of file framevel.hpp.
|
inline |
Definition at line 356 of file framevel.hpp.
IMETHOD RotationVel KDL::addDelta | ( | const RotationVel & | a, |
const VectorVel & | da, | ||
double | dt = 1.0 |
||
) |
Definition at line 363 of file framevel.hpp.
Definition at line 371 of file framevel.hpp.
adds vector da to vector a. see also the corresponding diff() routine.
p_w_a | vector a expressed to some frame w. |
p_w_da | vector da expressed to some frame w. |
Definition at line 1157 of file frames.hpp.
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.
R_w_a | Rotation matrix of frame a expressed to some frame w. |
da_w | axis and angle of the rotation expressed to some frame w. |
Definition at line 1161 of file frames.hpp.
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.
R_w_a | Rotation matrix of frame a expressed to some frame w. |
da_w | axis and angle of the rotation (da_w.rot), together with a displacement vector for the origin (da_w.vel), expressed to some frame w. |
Definition at line 1164 of file frames.hpp.
adds the twist da to the twist a. see also the corresponding diff() routine.
a | a twist wrt some frame |
da | a twist difference wrt some frame |
Definition at line 1170 of file frames.hpp.
adds the wrench da to the wrench w. see also the corresponding diff() routine. see also the corresponding diff() routine.
a | a wrench wrt some frame |
da | a wrench difference wrt some frame |
Definition at line 1173 of file frames.hpp.
Definition at line 105 of file jacobian.cpp.
Definition at line 119 of file jacobian.cpp.
Definition at line 91 of file jacobian.cpp.
void KDL::checkDiffs | ( | ) |
Definition at line 13 of file jacobianframetests.cpp.
void KDL::checkDoubleOps | ( | ) |
Definition at line 6 of file jacobiandoubletests.cpp.
|
inline |
Definition at line 34 of file jacobiantests.hpp.
void KDL::checkEulerZYX | ( | ) |
Definition at line 50 of file jacobianframetests.cpp.
void KDL::checkFrameOps | ( | ) |
Definition at line 89 of file jacobianframetests.cpp.
void KDL::checkFrameVelOps | ( | ) |
Definition at line 132 of file jacobianframetests.cpp.
Chain KDL::d2 | ( | ) |
Definition at line 18 of file jacobiandottest.cpp.
Chain KDL::d6 | ( | ) |
Definition at line 24 of file jacobiandottest.cpp.
Definition at line 38 of file framevel.hpp.
Definition at line 352 of file framevel.hpp.
IMETHOD VectorVel KDL::diff | ( | const RotationVel & | a, |
const RotationVel & | b, | ||
double | dt = 1.0 |
||
) |
Definition at line 359 of file framevel.hpp.
Definition at line 367 of file framevel.hpp.
determines the difference of vector b with vector a.
see diff for Rotation matrices for further background information.
p_w_a | start vector a expressed to some frame w |
p_w_b | end vector b expressed to some frame w . |
dt | [optional][obsolete] time interval over which the numerical differentiation takes place. |
Definition at line 1130 of file frames.hpp.
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 .
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.
R_a_b1 | The rotation matrix of b1 with respect to frame a. |
R_a_b2 | The Rotation matrix 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. |
Definition at line 1134 of file frames.hpp.
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.
F_a_b1 | frame b1 expressed with respect to some frame a. |
F_a_b2 | frame b2 expressed with respect to some frame a. |
Definition at line 1139 of file frames.hpp.
determines the difference between two twists i.e. the difference between the underlying velocity vectors and rotational velocity vectors.
Definition at line 1145 of file frames.hpp.
determines the difference between two wrenches i.e. the difference between the underlying torque vectors and force vectors.
Definition at line 1149 of file frames.hpp.
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.
Function to divide all the array values with a scalar factor: A/b=C. This function is aliasing-safe, A can be the same array as C.
src | A |
factor | b |
dest | C |
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.
Definition at line 138 of file frameacc.hpp.
Definition at line 145 of file frameacc.hpp.
Definition at line 152 of file frameacc.hpp.
Definition at line 496 of file framevel.hpp.
Definition at line 499 of file framevel.hpp.
Definition at line 502 of file framevel.hpp.
Definition at line 1013 of file frames.hpp.
Definition at line 1017 of file frames.hpp.
Definition at line 1021 of file frames.hpp.
void KDL::Eat | ( | std::istream & | is, |
int | delim | ||
) |
Eats characters of the stream until the character delim is encountered
is | a stream |
delim | eat 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
is | a stream |
descript | description 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.
is | a stream |
delim | eat 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...)
is | a stream |
delim | a string containing the delimmiting characters |
storage | for returning the word |
maxsize | a word can be maximally maxsize-1 long. |
Definition at line 394 of file frameacc.hpp.
Definition at line 397 of file frameacc.hpp.
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.
Definition at line 587 of file frameacc.hpp.
Definition at line 591 of file frameacc.hpp.
Definition at line 595 of file frameacc.hpp.
Definition at line 160 of file frameacc.hpp.
Definition at line 167 of file frameacc.hpp.
Definition at line 174 of file frameacc.hpp.
Definition at line 361 of file framevel.hpp.
Definition at line 364 of file framevel.hpp.
Definition at line 367 of file framevel.hpp.
bool KDL::Equal | ( | const RotationVel & | r1, |
const RotationVel & | r2, | ||
double | eps = epsilon |
||
) |
Definition at line 405 of file framevel.hpp.
bool KDL::Equal | ( | const Rotation & | r1, |
const RotationVel & | r2, | ||
double | eps = epsilon |
||
) |
Definition at line 408 of file framevel.hpp.
bool KDL::Equal | ( | const RotationVel & | r1, |
const Rotation & | r2, | ||
double | eps = epsilon |
||
) |
Definition at line 411 of file framevel.hpp.
Definition at line 76 of file framevel.hpp.
Definition at line 79 of file framevel.hpp.
Definition at line 82 of file framevel.hpp.
Definition at line 449 of file framevel.hpp.
Definition at line 453 of file framevel.hpp.
Definition at line 457 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.
Function to check if two arrays are the same with a precision of eps
src1 | |
src2 | |
eps | default: epsilon |
Definition at line 113 of file jntarray.cpp.
Definition at line 138 of file jacobian.cpp.
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 1033 of file frames.hpp.
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 1040 of file frames.hpp.
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 1050 of file frames.hpp.
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 1045 of file frames.hpp.
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 1055 of file frames.hpp.
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 1060 of file frames.hpp.
Definition at line 1064 of file frames.hpp.
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 159 of file frames.cpp.
bool KDL::Equal | ( | const JntArrayAcc & | src1, |
const JntArrayAcc & | src2, | ||
double | eps | ||
) |
Definition at line 171 of file jntarrayacc.cpp.
|
inline |
|
inlinestatic |
Definition at line 8 of file velocityprofile_spline.cpp.
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.
Chain KDL::KukaLWR | ( | ) |
Chain KDL::KukaLWR_DHnew | ( | ) |
Definition at line 26 of file kukaLWR_DHnew.cpp.
Chain KDL::KukaLWRsegment | ( | ) |
int KDL::ldl_solver_eigen | ( | const Eigen::MatrixXd & | A, |
const Eigen::VectorXd & | v, | ||
Eigen::MatrixXd & | L, | ||
Eigen::VectorXd & | D, | ||
Eigen::VectorXd & | vtmp, | ||
Eigen::VectorXd & | q | ||
) |
Solves the system of equations Aq = v for q via LDL decomposition, where A is a square positive definite matrix.
The algorithm factor A into the product of three matrices LDL^T, where L is a lower triangular matrix and D is a diagonal matrix. This allows q to be computed without explicity inverting A. Note that the LDL decomposition is a variant of the classical Cholesky Decomposition that does not require the computation of square roots. Input parameters:
A | matrix<double>(nxn) |
v | vector<double> n |
vtmp | vector<double> n [temp variable] Output parameters: |
L | matrix<double>(nxn) |
D | vector<double> n |
q | vector<double> n |
Definition at line 26 of file ldl_solver_eigen.cpp.
|
inline |
|
inline |
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.
Function to multiply all the array values with a scalar factor: A*b=C. This function is aliasing-safe, A can be the same array as C.
src | A |
factor | b |
dest | C |
Definition at line 92 of file jntarray.cpp.
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.
Function to multiply a KDL::Jacobian with a KDL::JntArray to get a KDL::Twist, it should not be used to calculate the forward velocity kinematics, the solver classes are built for this purpose. J*q = t
jac | J |
src | q |
dest | t |
Definition at line 102 of file jntarray.cpp.
Definition at line 93 of file framevel.hpp.
Definition at line 104 of file framevel.hpp.
Definition at line 115 of file framevel.hpp.
Definition at line 378 of file framevel.hpp.
Definition at line 389 of file framevel.hpp.
Definition at line 400 of file framevel.hpp.
bool KDL::operator!= | ( | const RotationVel & | r1, |
const RotationVel & | r2 | ||
) |
Definition at line 422 of file framevel.hpp.
bool KDL::operator!= | ( | const Rotation & | r1, |
const RotationVel & | r2 | ||
) |
Definition at line 433 of file framevel.hpp.
bool KDL::operator!= | ( | const RotationVel & | r1, |
const Rotation & | r2 | ||
) |
Definition at line 444 of file framevel.hpp.
Definition at line 469 of file framevel.hpp.
Definition at line 480 of file framevel.hpp.
Definition at line 491 of file framevel.hpp.
Definition at line 1285 of file frames.hpp.
Definition at line 1299 of file frames.hpp.
Definition at line 1312 of file frames.hpp.
Definition at line 1325 of file frames.hpp.
Definition at line 1328 of file frames.hpp.
Definition at line 1341 of file frames.hpp.
Definition at line 34 of file framevel.hpp.
Definition at line 38 of file framevel.hpp.
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.
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.
Definition at line 60 of file frameacc.hpp.
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.
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.
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.
Definition at line 79 of file frameacc.hpp.
Definition at line 81 of file stiffness.hpp.
Definition at line 84 of file frames.hpp.
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.
Definition at line 93 of file frames.hpp.
Definition at line 111 of file frames.hpp.
RotationVel KDL::operator* | ( | const RotationVel & | r1, |
const RotationVel & | r2 | ||
) |
Definition at line 130 of file framevel.hpp.
RotationVel KDL::operator* | ( | const Rotation & | r1, |
const RotationVel & | r2 | ||
) |
Definition at line 134 of file framevel.hpp.
RotationVel KDL::operator* | ( | const RotationVel & | r1, |
const Rotation & | r2 | ||
) |
Definition at line 138 of file framevel.hpp.
Definition at line 173 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.
Definition at line 243 of file frames.hpp.
Definition at line 248 of file frames.hpp.
Definition at line 255 of file frameacc.hpp.
Definition at line 281 of file framevel.hpp.
Definition at line 285 of file framevel.hpp.
Definition at line 289 of file framevel.hpp.
Definition at line 296 of file framevel.hpp.
Definition at line 300 of file framevel.hpp.
Definition at line 306 of file framevel.hpp.
Definition at line 310 of file framevel.hpp.
Definition at line 322 of file framevel.hpp.
Definition at line 346 of file frames.hpp.
Definition at line 350 of file frameacc.hpp.
Definition at line 351 of file frames.hpp.
Definition at line 354 of file frameacc.hpp.
Definition at line 358 of file frameacc.hpp.
Definition at line 380 of file frames.hpp.
Definition at line 384 of file frames.hpp.
Definition at line 407 of file frames.hpp.
Definition at line 472 of file frameacc.hpp.
Definition at line 477 of file frameacc.hpp.
Definition at line 488 of file frameacc.hpp.
Definition at line 493 of file frameacc.hpp.
Definition at line 543 of file framevel.hpp.
Definition at line 548 of file framevel.hpp.
Definition at line 559 of file framevel.hpp.
Definition at line 564 of file framevel.hpp.
Definition at line 756 of file frames.hpp.
Definition at line 761 of file frames.hpp.
Definition at line 871 of file frames.hpp.
Definition at line 931 of file frames.hpp.
Definition at line 25 of file frameacc.hpp.
Definition at line 32 of file frameacc.hpp.
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.
Definition at line 58 of file frames.hpp.
ArticulatedBodyInertia KDL::operator+ | ( | const RigidBodyInertia & | Ia, |
const ArticulatedBodyInertia & | Ib | ||
) |
Definition at line 59 of file articulatedbodyinertia.cpp.
Definition at line 92 of file stiffness.hpp.
ArticulatedBodyInertia KDL::operator+ | ( | const ArticulatedBodyInertia & | Ia, |
const RigidBodyInertia & | Ib | ||
) |
Definition at line 246 of file framevel.hpp.
Definition at line 254 of file framevel.hpp.
Definition at line 259 of file frames.hpp.
Definition at line 262 of file framevel.hpp.
Definition at line 362 of file frames.hpp.
Definition at line 506 of file frameacc.hpp.
Definition at line 577 of file framevel.hpp.
Definition at line 746 of file frames.hpp.
Definition at line 29 of file frameacc.hpp.
Definition at line 36 of file frameacc.hpp.
Definition at line 43 of file frameacc.hpp.
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.
Definition at line 67 of file frames.hpp.
ArticulatedBodyInertia KDL::operator- | ( | const ArticulatedBodyInertia & | Ia, |
const RigidBodyInertia & | Ib | ||
) |
Definition at line 250 of file framevel.hpp.
Definition at line 258 of file framevel.hpp.
Definition at line 264 of file frames.hpp.
Definition at line 266 of file framevel.hpp.
Definition at line 270 of file frames.hpp.
Definition at line 271 of file framevel.hpp.
Definition at line 367 of file frames.hpp.
Definition at line 373 of file frames.hpp.
Definition at line 450 of file frames.hpp.
Definition at line 511 of file frameacc.hpp.
Definition at line 517 of file frameacc.hpp.
Definition at line 582 of file framevel.hpp.
Definition at line 588 of file framevel.hpp.
Definition at line 751 of file frames.hpp.
Definition at line 814 of file frames.hpp.
Definition at line 102 of file frames.hpp.
Definition at line 181 of file frameacc.hpp.
Definition at line 185 of file frameacc.hpp.
Definition at line 253 of file frames.hpp.
Definition at line 314 of file framevel.hpp.
Definition at line 318 of file framevel.hpp.
Definition at line 356 of file frames.hpp.
Definition at line 482 of file frameacc.hpp.
Definition at line 498 of file frameacc.hpp.
Definition at line 553 of file framevel.hpp.
Definition at line 569 of file framevel.hpp.
Definition at line 766 of file frames.hpp.
std::ostream & KDL::operator<< | ( | std::ostream & | os, |
const Joint & | joint | ||
) |
Definition at line 27 of file kinfam_io.cpp.
|
inline |
Definition at line 28 of file rall1d_io.h.
std::ostream& KDL::operator<< | ( | std::ostream & | os, |
const Rall2d< T, V, S > & | r | ||
) |
Definition at line 29 of file rall2d_io.h.
|
inline |
Definition at line 29 of file framevel_io.hpp.
|
inline |
Definition at line 32 of file frameacc_io.hpp.
|
inline |
Definition at line 34 of file framevel_io.hpp.
std::ostream & KDL::operator<< | ( | std::ostream & | os, |
const Segment & | segment | ||
) |
Definition at line 36 of file kinfam_io.cpp.
|
inline |
Definition at line 37 of file frameacc_io.hpp.
|
inline |
Definition at line 40 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.
|
inline |
Definition at line 44 of file frameacc_io.hpp.
|
inline |
Definition at line 45 of file framevel_io.hpp.
std::ostream & KDL::operator<< | ( | std::ostream & | os, |
const Chain & | chain | ||
) |
Definition at line 45 of file kinfam_io.cpp.
|
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 57 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 62 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 75 of file kinfam_io.cpp.
std::ostream & KDL::operator<< | ( | std::ostream & | os, |
const Jacobian & | jac | ||
) |
Definition at line 87 of file kinfam_io.cpp.
std::ostream & KDL::operator<< | ( | std::ostream & | os, |
const JntSpaceInertiaMatrix & | jntspaceinertiamatrix | ||
) |
Definition at line 101 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.
Definition at line 85 of file framevel.hpp.
Definition at line 96 of file framevel.hpp.
Definition at line 107 of file framevel.hpp.
bool KDL::operator== | ( | const JntSpaceInertiaMatrix & | src1, |
const JntSpaceInertiaMatrix & | src2 | ||
) |
Definition at line 118 of file jntspaceinertiamatrix.cpp.
Definition at line 120 of file jntarray.cpp.
Definition at line 370 of file framevel.hpp.
Definition at line 381 of file framevel.hpp.
Definition at line 392 of file framevel.hpp.
bool KDL::operator== | ( | const RotationVel & | r1, |
const RotationVel & | r2 | ||
) |
Definition at line 414 of file framevel.hpp.
bool KDL::operator== | ( | const Rotation & | r1, |
const RotationVel & | r2 | ||
) |
Definition at line 425 of file framevel.hpp.
Definition at line 430 of file frames.cpp.
bool KDL::operator== | ( | const RotationVel & | r1, |
const Rotation & | r2 | ||
) |
Definition at line 436 of file framevel.hpp.
Definition at line 461 of file framevel.hpp.
Definition at line 472 of file framevel.hpp.
Definition at line 483 of file framevel.hpp.
Definition at line 1276 of file frames.hpp.
Definition at line 1289 of file frames.hpp.
Definition at line 1303 of file frames.hpp.
Definition at line 1316 of file frames.hpp.
Definition at line 1332 of file frames.hpp.
std::istream & KDL::operator>> | ( | std::istream & | is, |
Joint & | joint | ||
) |
Definition at line 32 of file kinfam_io.cpp.
std::istream & KDL::operator>> | ( | std::istream & | is, |
Segment & | segment | ||
) |
Definition at line 41 of file kinfam_io.cpp.
std::istream & KDL::operator>> | ( | std::istream & | is, |
Chain & | chain | ||
) |
Definition at line 53 of file kinfam_io.cpp.
std::istream & KDL::operator>> | ( | std::istream & | is, |
Tree & | tree | ||
) |
Definition at line 71 of file kinfam_io.cpp.
std::istream & KDL::operator>> | ( | std::istream & | is, |
JntArray & | array | ||
) |
Definition at line 83 of file kinfam_io.cpp.
std::istream & KDL::operator>> | ( | std::istream & | is, |
Jacobian & | jac | ||
) |
Definition at line 98 of file kinfam_io.cpp.
std::istream & KDL::operator>> | ( | std::istream & | is, |
JntSpaceInertiaMatrix & | jntspaceinertiamatrix | ||
) |
Definition at line 112 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.
void KDL::posrandom | ( | Jacobian< T > & | rv | ) |
Definition at line 25 of file jacobiantests.hpp.
Definition at line 50 of file framevel.hpp.
|
inline |
Definition at line 102 of file stiffness.hpp.
Definition at line 396 of file framevel.hpp.
Definition at line 400 of file framevel.hpp.
IMETHOD void KDL::posrandom | ( | RotationVel & | R | ) |
Definition at line 405 of file framevel.hpp.
Definition at line 410 of file framevel.hpp.
Definition at line 1244 of file frames.hpp.
Definition at line 1249 of file frames.hpp.
Definition at line 1253 of file frames.hpp.
Definition at line 1258 of file frames.hpp.
Definition at line 1268 of file frames.hpp.
Chain KDL::Puma560 | ( | ) |
Definition at line 27 of file puma560.cpp.
|
inline |
Definition at line 35 of file svd_eigen_HH.hpp.
void KDL::random | ( | Jacobian< T > & | rv | ) |
Definition at line 16 of file jacobiantests.hpp.
Definition at line 46 of file framevel.hpp.
|
inline |
Definition at line 111 of file stiffness.hpp.
Definition at line 378 of file framevel.hpp.
Definition at line 382 of file framevel.hpp.
IMETHOD void KDL::random | ( | RotationVel & | R | ) |
Definition at line 387 of file framevel.hpp.
Definition at line 392 of file framevel.hpp.
addDelta operator for displacement rotational velocity.
The Vector arguments here represent a displacement rotational velocity. i.e. a rotation around a fixed axis for a certain angle. For this representation you cannot use diff() but have to use diff_displ().
a | : displacement rotational velocity |
da | : rotational velocity |
IMETHOD Vector addDelta_displ(const Vector& a,const Vector&da,double dt) { return getRot(addDelta(Rot(a),da,dt)); } addDelta operator for displacement twist.
The Vector arguments here represent a displacement rotational velocity. i.e. a rotation around a fixed axis for a certain angle. For this representation you cannot use diff() but have to use diff_displ().
a | : displacement twist |
da | : twist |
IMETHOD Twist addDelta_displ(const Twist& a,const Twist&da,double dt) { return Twist(addDelta(a.vel,da.vel,dt),addDelta_displ(a.rot,da.rot,dt)); }
Definition at line 1215 of file frames.hpp.
Definition at line 1220 of file frames.hpp.
Definition at line 1224 of file frames.hpp.
Definition at line 1229 of file frames.hpp.
Definition at line 1239 of file frames.hpp.
axis_a_b is a rotation vector, its norm is a rotation angle axis_a_b rotates the a frame towards the b frame. This routine returns the rotation matrix R_a_b
Definition at line 1108 of file frames.hpp.
|
inline |
void KDL::SetToZero | ( | Jacobian & | jac | ) |
Definition at line 81 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 | ) |
Function to set all the values of the array to 0
array |
Definition at line 108 of file jntarray.cpp.
void KDL::SetToZero | ( | JntArrayAcc & | array | ) |
Definition at line 164 of file jntarrayacc.cpp.
|
inline |
void KDL::SetToZero | ( | VectorVel & | v | ) |
Definition at line 275 of file framevel.hpp.
void KDL::SetToZero | ( | TwistVel & | v | ) |
Definition at line 593 of file framevel.hpp.
To have a uniform operator to put an element to zero, for scalar values and for objects.
Definition at line 1069 of file frames.hpp.
Definition at line 1072 of file frames.hpp.
Sets the Wrench to Zero, to have a uniform function that sets an object or double to zero.
Definition at line 1076 of file frames.hpp.
Definition at line 1081 of file frames.hpp.
|
inline |
Definition at line 53 of file svd_eigen_HH.hpp.
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.
Function to subtract two joint arrays, all the arguments must have the same size: A - B = C. This function is aliasing-safe, A or B can be the same array as C.
src1 | A |
src2 | B |
dest | C |
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
A | matrix<double>(mxn) |
U | matrix<double>(mxn) |
S | vector<double> n |
V | matrix<double>(nxn) |
tmp | vector<double> n |
maxiter | defaults to 150 |
Definition at line 26 of file svd_eigen_HH.cpp.
int KDL::svd_eigen_Macie | ( | const Eigen::MatrixXd & | A, |
Eigen::MatrixXd & | U, | ||
Eigen::VectorXd & | S, | ||
Eigen::MatrixXd & | V, | ||
Eigen::MatrixXd & | B, | ||
Eigen::VectorXd & | tempi, | ||
double | threshold, | ||
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)
A | [INPUT] is an -matrix, where . |
S | [OUTPUT] is an -vector, representing the diagonal elements of the diagonal matrix Sm. |
U | [INPUT/OUTPUT] is an orthonormal matrix. |
V | [INPUT/OUTPUT] is an orthonormal matrix. |
B | [TEMPORARY] is an matrix used for temporary storage. |
tempi | [TEMPORARY] is an vector used for temporary storage. |
threshold | [INPUT] Threshold to determine orthogonality. |
toggle | [INPUT] toggle this boolean variable on each call of this routine. |
Definition at line 25 of file svd_eigen_Macie.cpp.
void KDL::swap | ( | scoped_ptr< T > & | a, |
scoped_ptr< T > & | b | ||
) |
Definition at line 72 of file scoped_ptr.hpp.
std::string KDL::tree2str | ( | const SegmentMap::const_iterator | it, |
const std::string & | separator, | ||
const std::string & | preamble, | ||
unsigned int | level | ||
) |
Definition at line 117 of file kinfam_io.cpp.
std::string KDL::tree2str | ( | const Tree & | tree, |
const std::string & | separator, | ||
const std::string & | preamble | ||
) |
Definition at line 128 of file kinfam_io.cpp.
|
inline |
Definition at line 40 of file chainiksolverpos_lma.cpp.
const double KDL::deg2rad |
the value pi/180
double KDL::epsilon |
default precision while comparing with Equal(..,..) functions. Initialized at 0.0000001.
|
static |
Definition at line 12 of file jacobiandottest.cpp.
|
static |
Definition at line 13 of file jacobiandottest.cpp.
|
static |
Definition at line 14 of file jacobiandottest.cpp.
|
static |
Definition at line 15 of file jacobiandottest.cpp.
|
static |
Definition at line 16 of file jacobiandottest.cpp.
|
static |
Definition at line 17 of file jacobiandottest.cpp.
int KDL::MAXLENFILENAME |
maximal length of a file name
|
static |
Definition at line 30 of file rigidbodyinertia.cpp.
const double KDL::PI |
the value of pi
const double KDL::PI_2 |
the value of pi/2
const double KDL::PI_4 |
the value of pi/4
const double KDL::rad2deg |
the value 180/pi
int KDL::STREAMBUFFERSIZE |
/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".
int KDL::VSIZE |
the number of derivatives used in the RN-... objects.