GCOP
1.0
|
#include <mbscontroller.h>
Public Member Functions | |
MbsController (const Mbs &sys, MbsState *xd=0, VectorXd *ad=0) | |
virtual bool | Set (VectorXd &u, double t, const MbsState &x) |
virtual | ~MbsController () |
Public Attributes | |
const Mbs & | sys |
multi-body system | |
MbsState * | xd |
desired state (origin by default) | |
VectorXd * | ad |
desired acceleration (zero by default) | |
VectorXd | Kp |
proportional terms (ones by default) | |
VectorXd | Kd |
derivative terms (ones by default) |
MbsController::MbsController | ( | const Mbs & | sys, |
MbsState * | xd = 0 , |
||
VectorXd * | ad = 0 |
||
) |
MbsController::~MbsController | ( | ) | [virtual] |
bool MbsController::Set | ( | VectorXd & | u, |
double | t, | ||
const MbsState & | x | ||
) | [virtual] |
Feedback controller of the form u = k(t, x)
u | controls |
t | time |
x | state |
Implements gcop::Controller< MbsState, VectorXd >.
References ad, gcop::Mbs::Bias(), gcop::MbsState::dr, gcop::Mbs::fixed, gcop::MbsState::gs, gcop::SE3::Instance(), gcop::SE3::inv(), Kd, Kp, gcop::SE3::log(), gcop::Mbs::Mass(), gcop::Mbs::nb, gcop::MbsState::r, sys, gcop::MbsState::vs, and xd.
VectorXd* gcop::MbsController::ad |
desired acceleration (zero by default)
Referenced by Set().
VectorXd gcop::MbsController::Kd |
derivative terms (ones by default)
Referenced by MbsController(), and Set().
VectorXd gcop::MbsController::Kp |
proportional terms (ones by default)
Referenced by MbsController(), and Set().
const Mbs& gcop::MbsController::sys |
multi-body system
Referenced by Set().
desired state (origin by default)
Referenced by Set().