22 #ifndef KDL_JACOBIAN_HPP 23 #define KDL_JACOBIAN_HPP 32 bool Equal(
const Jacobian& a,
const Jacobian& b,
double eps=
epsilon);
40 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
41 Eigen::Matrix<double,6,Eigen::Dynamic>
data;
43 explicit Jacobian(
unsigned int nr_of_columns);
47 void resize(
unsigned int newNrOfColumns);
60 double operator()(
unsigned int i,
unsigned int j)
const;
61 double&
operator()(
unsigned int i,
unsigned int j);
62 unsigned int rows()
const;
represents rotations in 3 dimensional space.
void resize(unsigned int newNrOfColumns)
Allocates memory for new size (can break realtime behavior)
friend void SetToZero(Jacobian &jac)
double operator()(unsigned int i, unsigned int j) const
unsigned int columns() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix< double, 6, Eigen::Dynamic > data
bool operator==(const Jacobian &arg) const
represents both translational and rotational velocities.
IMETHOD void SetToZero(Vector &v)
IMETHOD bool Equal(const FrameAcc &r1, const FrameAcc &r2, double eps=epsilon)
A concrete implementation of a 3 dimensional vector class.
double epsilon
default precision while comparing with Equal(..,..) functions. Initialized at 0.0000001.
void setColumn(unsigned int i, const Twist &t)
friend bool changeBase(const Jacobian &src1, const Rotation &rot, Jacobian &dest)
friend bool changeRefFrame(const Jacobian &src1, const Frame &frame, Jacobian &dest)
friend bool changeRefPoint(const Jacobian &src1, const Vector &base_AB, Jacobian &dest)
Twist getColumn(unsigned int i) const
Jacobian & operator=(const Jacobian &arg)
Allocates memory if size of this and argument is different.
represents a frame transformation in 3D space (rotation + translation)
friend bool Equal(const Jacobian &a, const Jacobian &b, double eps)
unsigned int rows() const
bool operator!=(const Jacobian &arg) const