next up previous contents
Next: torque_novelocity Up: The Robot and mRobot Previous: inertia   Contents

Subsections

torque

Syntax

ReturnMatrix torque(const ColumnVector & q, 
                    const ColumnVector & qp,
                    const ColumnVector & qpp);

ReturnMatrix torque(const ColumnVector & q,
                    const ColumnVector & qp,
                    const ColumnVector & qpp,
                    const ColumnVector & Fext,
                    const ColumnVector & Next);

Description

This function computes $\mbox{\boldmath$ \tau $}$ from $\mbox{\boldmath$ q $}$, $\dot{\mbox{\boldmath$ q $}}$ and $\ddot{\mbox{\boldmath$ q $}}$ which is the inverse dynamics problem. The recursive Newton-Euler (RNE) formulation is one of the most computationally efficient algorithm [12,13] used to solve this problem (see appendix A). The second form allows the inclusion the contribution of a load applied at the last link.

Return Value

ColumnVector



Richard Gourdeau 2004-07-06