29 using namespace Eigen;
32 chain(chain_), nj(chain.getNrOfJoints()), ns(chain.getNrOfSegments()), nc(_nc),
40 Um = MatrixXd::Identity(
nc,
nc);
41 Vm = MatrixXd::Identity(
nc,
nc);
42 Sm = VectorXd::Ones(
nc);
79 for (
unsigned int i = 0; i <
ns; i++)
88 s.
F = segment.
pose(q(j));
126 s.
U = s.
v * (s.
H * s.
v) - FextLocal;
136 for (
int i =
ns; i >= 0; i--)
155 for (
unsigned int r = 0; r < 3; r++)
156 for (
unsigned int c = 0; c <
nc; c++)
159 s.
E_tilde(r, c) = alfa(r + 3, c);
160 s.
E_tilde(r + 3, c) = alfa(r, c);
165 for (
unsigned int c = 0; c <
nc; c++)
169 col = base_to_end*col;
170 s.
E_tilde.col(c) << Vector3d::Map(col.torque.data), Vector3d::Map(col.force.data);
182 PZDPZt.noalias() = vPZ * vPZ.transpose();
195 s.
E_tilde.noalias() -= (vPZ * child.
EZ.transpose()) / child.
D;
200 s.
M.noalias() -= (child.
EZ * child.
EZ.transpose()) / child.
D;
204 Twist CiZDu = child.
C + (child.
Z / child.
D) * child.
u;
206 vCiZDu << Vector3d::Map(CiZDu.rot.data), Vector3d::Map(CiZDu.vel.data);
207 s.
G.noalias() += child.
E.transpose() * vCiZDu;
217 for (
unsigned int c = 0; c <
nc; c++)
241 s.
EZ.noalias() = s.
E.transpose() * vZ;
263 for (
unsigned int i = 0; i <
nc; i++)
288 for (
unsigned int i = 1; i <=
ns; i++)
308 Vector(tmp(0), tmp(1), tmp(2)));
313 double parent_forceProjection = -
dot(s.
Z, parent_force);
314 double parentAccComp = parent_forceProjection / s.
D;
317 double constraint_torque = -
dot(s.
Z, constraint_force);
320 torques(j) = constraint_torque;
represents rotations in 3 dimensional space.
ArticulatedBodyInertia P_tilde
const Segment & getSegment(unsigned int nr) const
This class encapsulates a simple segment, that is a "rigid body" (i.e., a frame and a rigid body...
unsigned int rows() const
Rotation Inverse() const
Gives back the inverse rotation matrix of *this.
This class encapsulates a serial kinematic interconnection structure. It is built out of segments...
Vector vel
The velocity of that point.
Eigen::Matrix< double, 6, 1 > Vector6d
unsigned int getNrOfSegments() const
This class represents an fixed size array containing joint values of a KDL::Chain.
virtual void updateInternalDataStructures()
Input size does not match internal state.
Vector torque
Torque that is applied at the origin of the current ref frame.
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
unsigned int columns() const
int svd_eigen_HH(const MatrixXd &A, MatrixXd &U, VectorXd &S, MatrixXd &V, VectorXd &tmp, int maxiter, double epsilon)
Rotation M
Orientation of the Frame.
Frame pose(const double &q) const
Twist twist(const double &q, const double &qdot) const
represents both translational and rotational velocities.
int CartToJnt(const JntArray &q, const JntArray &q_dot, JntArray &q_dotdot, const Jacobian &alfa, const JntArray &beta, const Wrenches &f_ext, JntArray &torques)
6D Inertia of a articulated body
A concrete implementation of a 3 dimensional vector class.
Vector rot
The rotational velocity of that point.
void constraint_calculation(const JntArray &beta)
void final_upwards_sweep(JntArray &q_dotdot, JntArray &torques)
const Joint & getJoint() const
unsigned int getNrOfJoints() const
Frame Inverse() const
Gives back inverse transformation of a Frame.
ChainIdSolver_Vereshchagin(const Chain &chain, Twist root_acc, unsigned int nc)
Vector force
Force that is applied at the origin of the current ref frame.
void downwards_sweep(const Jacobian &alfa, const JntArray &torques)
std::vector< Wrench > Wrenches
void initial_upwards_sweep(const JntArray &q, const JntArray &q_dot, const JntArray &q_dotdot, const Wrenches &f_ext)
represents both translational and rotational acceleration.
std::vector< segment_info, Eigen::aligned_allocator< segment_info > > results
Eigen::MatrixXd M_0_inverse
int error
Latest error, initialized to E_NOERROR in constructor.
const RigidBodyInertia & getInertia() const
const JointType & getType() const
Eigen::Matrix< double, 6, 6 > Matrix6d