Go to the documentation of this file.
12 #include <boost/filesystem.hpp>
13 #include <boost/format.hpp>
14 #include <boost/version.hpp>
15 #include <pinocchio/algorithm/center-of-mass.hpp>
16 #include <pinocchio/algorithm/centroidal.hpp>
17 #include <pinocchio/algorithm/crba.hpp>
18 #include <pinocchio/algorithm/jacobian.hpp>
19 #include <pinocchio/algorithm/kinematics.hpp>
20 #include <pinocchio/fwd.hpp>
21 #include <pinocchio/multibody/model.hpp>
22 #include <pinocchio/spatial/motion.hpp>
25 #include "../src/dynamic-command.h"
30 const std::string dg::sot::DynamicPinocchio::CLASS_NAME =
"DynamicPinocchio";
39 NULL,
"sotDynamicPinocchio(" +
name +
")::input(vector)::position"),
41 NULL,
"sotDynamicPinocchio(" +
name +
")::input(vector)::ffposition"),
43 NULL,
"sotDynamicPinocchio(" +
name +
")::input(vector)::velocity"),
45 NULL,
"sotDynamicPinocchio(" +
name +
")::input(vector)::ffvelocity"),
46 jointAccelerationSIN(NULL,
"sotDynamicPinocchio(" +
name +
47 ")::input(vector)::acceleration"),
48 freeFlyerAccelerationSIN(NULL,
"sotDynamicPinocchio(" +
name +
49 ")::input(vector)::ffacceleration")
54 jointPositionSIN << freeFlyerPositionSIN,
55 "sotDynamicPinocchio(" +
name +
")::intern(dummy)::pinocchioPos"),
58 jointVelocitySIN << freeFlyerVelocitySIN,
59 "sotDynamicPinocchio(" +
name +
")::intern(dummy)::pinocchioVel"),
62 jointAccelerationSIN << freeFlyerAccelerationSIN,
63 "sotDynamicPinocchio(" +
name +
")::intern(dummy)::pinocchioAcc")
68 pinocchioPosSINTERN << pinocchioVelSINTERN << pinocchioAccSINTERN,
69 "sotDynamicPinocchio(" +
name +
")::intern(dummy)::newtoneuler"),
73 "sotDynamicPinocchio(" +
name +
")::intern(dummy)::computeJacobians"),
74 forwardKinematicsSINTERN(
77 pinocchioPosSINTERN << pinocchioVelSINTERN << pinocchioAccSINTERN,
78 "sotDynamicPinocchio(" +
name +
79 ")::intern(dummy)::computeForwardKinematics"),
82 pinocchioPosSINTERN << pinocchioVelSINTERN,
83 "sotDynamicPinocchio(" +
name +
")::intern(dummy)::computeCcrba"),
86 "sotDynamicPinocchio(" +
name +
")::output(vector)::zmp"),
89 "sotDynamicPinocchio(" +
name +
")::output(matrix)::Jcom"),
91 forwardKinematicsSINTERN,
92 "sotDynamicPinocchio(" +
name +
")::output(vector)::com"),
95 "sotDynamicPinocchio(" +
name +
")::output(matrix)::inertia"),
99 "sotDynamicPinocchio(" +
name +
")::output(double)::footHeight"),
103 "sotDynamicPinocchio(" +
name +
")::output(vector)::upperJl")
109 "sotDynamicPinocchio(" +
name +
")::output(vector)::lowerJl")
115 "sotDynamicPinocchio(" +
name +
")::output(vector)::upperVl")
121 "sotDynamicPinocchio(" +
name +
")::output(vector)::upperTl")
124 inertiaRotorSOUT(
"sotDynamicPinocchio(" +
name +
125 ")::output(matrix)::inertiaRotor"),
126 gearRatioSOUT(
"sotDynamicPinocchio(" +
name +
127 ")::output(matrix)::gearRatio"),
130 inertiaSOUT << gearRatioSOUT << inertiaRotorSOUT,
131 "sotDynamicPinocchio(" +
name +
")::output(matrix)::inertiaReal"),
134 "sotDynamicPinocchio(" +
name +
")::output(vector)::momenta"),
138 "sotDynamicPinocchio(" +
name +
")::output(vector)::angularmomentum"),
142 "sotDynamicPinocchio(" +
name +
")::output(vector)::dynamicDrift") {
177 std::string docstring;
182 " Display the current robot configuration.\n"
190 " Get the dimension of the robot configuration.\n"
193 " an unsigned int: the dimension.\n"
198 using namespace ::dg::command;
203 " Create an operational point attached to a robot joint local "
207 " - a string: name of the operational point,\n"
208 " - a string: name the joint, or among (gaze, left-ankle, right "
210 " , left-wrist, right-wrist, waist, chest).\n"
218 "Create a jacobian (world frame) signal only for one joint.",
219 "string (signal name)",
"string (joint name)");
226 "Create a jacobian (endeff frame) signal only for one joint.",
227 "string (signal name)",
"string (joint name)");
229 "createJacobianEndEff",
235 "Create a jacobian (endeff frame) signal only for one joint. "
236 "The returned jacobian is placed at the joint position, but oriented "
237 "with the world axis.",
238 "string (signal name)",
"string (joint name)");
240 "createJacobianEndEffWorld",
246 "Create a position (matrix homo) signal only for one joint.",
247 "string (signal name)",
"string (joint name)");
254 docCommandVoid2(
"Create a velocity (vector) signal only for one joint.",
255 "string (signal name)",
"string (joint name)");
262 "Create an acceleration (vector) signal only for one joint.",
263 "string (signal name)",
"string (joint name)");
265 "createAcceleration",
270 " Return robot joint names.\n\n";
276 sotDEBUG(10) <<
"Dynamic class_name address" << &CLASS_NAME << std::endl;
319 const sigtime_t&)
const {
325 int fillingIndex = 0;
329 if (*it - fillingIndex > 0) {
330 res.segment(fillingIndex, *it - fillingIndex) =
334 origIndex += *it - fillingIndex;
335 fillingIndex += *it - fillingIndex;
344 res(fillingIndex) = -std::numeric_limits<double>::max();
345 res(fillingIndex + 1) = -std::numeric_limits<double>::max();
346 res(fillingIndex + 2) = -std::numeric_limits<double>::max();
360 sotDEBUG(15) <<
"lowerLimit (" <<
res <<
")=" << std::endl;
366 const sigtime_t&)
const {
372 int fillingIndex = 0;
376 if (*it - fillingIndex > 0) {
377 res.segment(fillingIndex, *it - fillingIndex) =
381 origIndex += *it - fillingIndex;
382 fillingIndex += *it - fillingIndex;
386 res(fillingIndex) = std::numeric_limits<double>::max();
387 res(fillingIndex + 1) = std::numeric_limits<double>::max();
388 res(fillingIndex + 2) = std::numeric_limits<double>::max();
400 sotDEBUG(15) <<
"upperLimit (" <<
res <<
")=" << std::endl;
406 const sigtime_t&)
const {
413 sotDEBUG(15) <<
"upperVelocityLimit (" <<
res <<
")=" << std::endl;
419 const sigtime_t&)
const {
432 const sigtime_t& time) {
438 qJoints.head<6>() = qFF;
442 int fillingIndex = 0;
446 if (*it - origIndex > 0) {
447 q.segment(fillingIndex, *it - origIndex) =
448 qJoints.segment(origIndex, *it - origIndex);
449 fillingIndex += *it - origIndex;
450 origIndex += *it - origIndex;
452 assert(*it == origIndex);
453 Eigen::Quaternion<double> temp =
454 Eigen::AngleAxisd(qJoints(origIndex + 2), Eigen::Vector3d::UnitZ()) *
455 Eigen::AngleAxisd(qJoints(origIndex + 1), Eigen::Vector3d::UnitY()) *
456 Eigen::AngleAxisd(qJoints(origIndex), Eigen::Vector3d::UnitX());
457 q(fillingIndex) = temp.x();
458 q(fillingIndex + 1) = temp.y();
459 q(fillingIndex + 2) = temp.z();
460 q(fillingIndex + 3) = temp.w();
464 if (qJoints.size() > origIndex)
465 q.segment(fillingIndex, qJoints.size() - origIndex) =
466 qJoints.tail(qJoints.size() - origIndex);
468 q.resize(qJoints.size());
472 sotDEBUG(15) <<
"Position out" <<
q << std::endl;
478 const sigtime_t& time) {
482 if (
v.size() != vJoints.size() + vFF.size())
483 v.resize(vJoints.size() + vFF.size());
493 const sigtime_t& time) {
497 if (
a.size() != aJoints.size() + aFF.size())
498 a.resize(aJoints.size() + aFF.size());
510 const std::string& jointName) {
520 "sotDynamicPinocchio(" +
name +
")::output(matrix)::" + signame);
527 "sotDynamicPinocchio(" +
name +
")::output(matrix)::" + signame);
531 "Robot has no joint corresponding to " + jointName);
541 const std::string& jointName,
542 const bool isLocal) {
551 isLocal, frameId, _1, _2),
553 "sotDynamicPinocchio(" +
name +
")::output(matrix)::" + signame);
558 false, isLocal, jointId, _1, _2),
560 "sotDynamicPinocchio(" +
name +
")::output(matrix)::" + signame);
564 "Robot has no joint corresponding to " + jointName);
573 const std::string& jointName) {
583 "sotDynamicPinocchio(" +
name +
")::output(matrixHomo)::" + signame);
590 "sotDynamicPinocchio(" +
name +
")::output(matrixHomo)::" + signame);
594 "Robot has no joint corresponding to " + jointName);
604 const std::string& jointName) {
614 "sotDynamicPinocchio(" +
name +
")::output(dg::Vector)::" + signame);
624 const std::string& jointName) {
633 "sotDynamicPinocchio(" +
name +
")::output(dg::Vector)::" + signame);
645 bool deletable =
false;
650 if ((*iter) ==
sig) {
660 " (while trying to remove generic jac. signal <%s>).", signame.c_str());
668 bool deletable =
false;
674 if ((*iter) ==
sig) {
684 " (while trying to remove generic pos. signal <%s>).", signame.c_str());
694 bool deletable =
false;
699 if ((*iter) ==
sig) {
709 " (while trying to remove generic pos. signal <%s>).", signame.c_str());
719 bool deletable =
false;
725 if ((*iter) ==
sig) {
734 getName() +
":cannot destroy signal",
735 " (while trying to remove generic acc "
749 const sigtime_t& time) {
753 if (
res.size() != 3)
res.resize(3);
757 const pinocchio::Force::Vector3&
tau = ftau.
angular();
758 const pinocchio::Force::Vector3&
f = ftau.
linear();
775 sotDEBUG(25) <<
"Jacobians updated" << std::endl;
780 const sigtime_t& time) {
788 sotDEBUG(25) <<
"Kinematics updated" << std::endl;
798 sotDEBUG(25) <<
"Inertia and Momentum updated" << std::endl;
806 const sigtime_t& time) {
825 const bool isFrame,
const bool isLocal,
const int id,
dg::Matrix& res,
826 const sigtime_t& time) {
837 bool changeFrame = !isLocal;
854 T.rotation() =
m_data->oMf[fid].rotation();
855 T.translation().setZero();
861 M.rotation() =
m_data->oMi[jid].rotation();
862 M.translation().setZero();
875 const sigtime_t& time) {
883 res.matrix() =
m_data->oMi[
id].toHomogeneousMatrix();
887 <<
" with id: " <<
id <<
" position is " <<
res << std::endl;
894 const sigtime_t& time) {
899 res << aRV.linear(), aRV.angular();
905 const int jointId,
dg::Vector& res,
const sigtime_t& time) {
910 res << aRA.linear(), aRA.angular();
924 sotDEBUG(1) <<
"pos = " <<
q << std::endl;
925 sotDEBUG(1) <<
"vel = " <<
v << std::endl;
926 sotDEBUG(1) <<
"acc = " <<
a << std::endl;
933 const sigtime_t& time) {
942 const sigtime_t& time) {
954 const sigtime_t& time) {
958 res.triangularView<Eigen::StrictlyLower>() =
959 res.transpose().triangularView<Eigen::StrictlyLower>();
965 const sigtime_t& time) {
986 "Robot has no joint corresponding to rigthFoot");
989 Eigen::Vector3d anklePosInLocalRefFrame =
m_data->liMi[jointId].translation();
991 res = anklePosInLocalRefFrame(2);
997 const sigtime_t& time) {
1006 const sigtime_t& time) {
1009 if (Momenta.size() != 6) Momenta.resize(6);
1011 Momenta =
m_data->hg.toVector_impl();
1018 const sigtime_t& time) {
1022 if (Momenta.size() != 3) Momenta.resize(3);
1023 Momenta =
m_data->hg.angular_impl();
1033 const std::string&
name) {
1039 }
catch (
const std::bad_cast& e) {
1041 " (while getting signal <%s> of type matrix.",
1053 }
catch (
const std::bad_cast& e) {
1055 " (while getting signal <%s> of type matrixHomo.",
1067 }
catch (
const std::bad_cast& e) {
1069 " (while getting signal <%s> of type Vector.",
1081 }
catch (
const std::bad_cast& e) {
1083 " (while getting signal <%s> of type Vector.",
1097 const std::string& jointName) {
1102 const std::string& signalName,
const std::string& jointName) {
1106 const std::string& signalName,
const std::string& jointName) {
1111 const std::string& signalName,
const std::string& jointName) {
1116 const std::string& jointName) {
1120 const std::string& jointName) {
1124 const std::string& signalName,
const std::string& jointName) {
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & jacobianCenterOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
std::vector< std::string > names
int & computeCcrba(int &dummy, const sigtime_t &time)
dg::Matrix & computeInertiaReal(dg::Matrix &res, const sigtime_t &time)
dg::SignalTimeDependent< Dummy, sigtime_t > ccrbaSINTERN
dg::SignalTimeDependent< dg::Vector, sigtime_t > upperVlSOUT
const T & access(const Time &t1)
std::vector< int > sphericalJoints
dg::Matrix & computeGenericEndeffJacobian(const bool isFrame, const bool isLocal, const int jointId, dg::Matrix &res, const sigtime_t &time)
dg::SignalTimeDependent< dg::Vector, sigtime_t > pinocchioAccSINTERN
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
bool existJointName(const std::string &name) const
Eigen::Transform< double, 3, Eigen::Affine > SOT_CORE_EXPORT MatrixHomogeneous
int & computeJacobians(int &dummy, const sigtime_t &time)
dg::SignalTimeDependent< Dummy, sigtime_t > forwardKinematicsSINTERN
double & computeFootHeight(double &res, const sigtime_t &time)
ConfigVectorType lowerPositionLimit
dg::SignalPtr< dg::Vector, sigtime_t > freeFlyerAccelerationSIN
int idx_v(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
int nv(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
JointIndex id(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
int nq(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
dg::SignalPtr< dg::Vector, sigtime_t > jointVelocitySIN
dg::Vector & getMaxEffortLimits(dg::Vector &res, const sigtime_t &) const
Get joint effort upper limits.
This class provides an inverse dynamic model of the robot. More precisely it wraps the newton euler a...
pinocchio::Model * m_model
dg::SignalTimeDependent< dg::Vector, sigtime_t > upperJlSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > comSOUT
std::unique_ptr< pinocchio::Data > m_data
void cmd_createPositionSignal(const std::string &sig, const std::string &j)
dg::SignalTimeDependent< dg::Vector, sigtime_t > zmpSOUT
dg::SignalTimeDependent< dg::Matrix, sigtime_t > inertiaRealSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > pinocchioPosSINTERN
bool existFrame(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
dg::SignalTimeDependent< dg::Matrix, sigtime_t > & jacobiansSOUT(const std::string &name)
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & ccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
void cmd_createJacobianEndEffectorSignal(const std::string &sig, const std::string &j)
dg::SignalPtr< dg::Vector, sigtime_t > freeFlyerVelocitySIN
dg::SignalTimeDependent< dg::Matrix, sigtime_t > & createJacobianSignal(const std::string &signame, const std::string &)
void getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6Like > &J)
const std::string & getName() const
dg::SignalTimeDependent< dg::Matrix, sigtime_t > & createEndeffJacobianSignal(const std::string &signame, const std::string &, const bool isLocal=true)
virtual const T & access(const Time &t)
dg::Signal< dg::Vector, sigtime_t > gearRatioSOUT
void cmd_createVelocitySignal(const std::string &sig, const std::string &j)
#define sotDEBUGOUT(level)
void destroyAccelerationSignal(const std::string &signame)
dg::Matrix & computeJcom(dg::Matrix &res, const sigtime_t &time)
void destroyJacobianSignal(const std::string &signame)
void rnea(const int num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &a, const Eigen::MatrixBase< TangentVectorPool3 > &tau)
void destroyVelocitySignal(const std::string &signame)
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & centerOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
dg::Signal< dg::Vector, sigtime_t > inertiaRotorSOUT
dg::Vector & getLowerPositionLimits(dg::Vector &res, const sigtime_t &) const
Get joint position lower limits.
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
dg::SignalPtr< dg::Vector, sigtime_t > freeFlyerPositionSIN
dg::SignalTimeDependent< Dummy, sigtime_t > newtonEulerSINTERN
void cmd_createJacobianEndEffectorWorldSignal(const std::string &sig, const std::string &j)
dg::SignalTimeDependent< dg::Vector, sigtime_t > MomentaSOUT
#define sotDEBUGIN(level)
void setModel(pinocchio::Model *)
dg::Matrix & computeGenericJacobian(const bool isFrame, const int jointId, dg::Matrix &res, const sigtime_t &time)
std::list< dg::SignalBase< sigtime_t > * > genericSignalRefs
dynamicgraph::SignalArray_const< double > sig
dg::SignalTimeDependent< double, sigtime_t > footHeightSOUT
void cmd_createOpPointSignals(const std::string &sig, const std::string &j)
dg::SignalPtr< dg::Vector, sigtime_t > jointPositionSIN
dg::Vector & computeMomenta(dg::Vector &res, const sigtime_t &time)
dg::Vector & computeCom(dg::Vector &res, const sigtime_t &time)
SignalArray< int > sotNOSIGNAL(0)
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
dg::Vector & getPinocchioAcc(dg::Vector &a, const sigtime_t &time)
TangentVectorType velocityLimit
dg::SignalTimeDependent< dg::Matrix, sigtime_t > JcomSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > & velocitiesSOUT(const std::string &name)
dg::SignalTimeDependent< dg::Vector, sigtime_t > pinocchioVelSINTERN
dg::SignalTimeDependent< dg::Vector, sigtime_t > & createVelocitySignal(const std::string &, const std::string &)
CommandVoid2< E, T1, T2 > * makeCommandVoid2(E &entity, boost::function< void(const T1 &, const T2 &)> function, const std::string &docString)
JointIndex getJointId(const std::string &name) const
std::string docCommandVoid2(const std::string &doc, const std::string &type1, const std::string &type2)
virtual ~DynamicPinocchio(void)
dg::Vector & computeGenericVelocity(const int jointId, dg::Vector &res, const sigtime_t &time)
int & computeNewtonEuler(int &dummy, const sigtime_t &time)
dg::SignalTimeDependent< dg::Vector, sigtime_t > & createAccelerationSignal(const std::string &, const std::string &)
dg::Vector & getPinocchioPos(dg::Vector &q, const sigtime_t &time)
map of joints in construction. map: jointName -> (jointType,jointPosition (in parent frame),...
dg::Vector & computeTorqueDrift(dg::Vector &res, const sigtime_t &time)
void destroyPositionSignal(const std::string &signame)
int & computeForwardKinematics(int &dummy, const sigtime_t &time)
dg::SignalTimeDependent< dg::Matrix, sigtime_t > inertiaSOUT
dg::Vector & computeGenericAcceleration(const int jointId, dg::Vector &res, const sigtime_t &time)
dg::Vector & getUpperPositionLimits(dg::Vector &res, const sigtime_t &) const
Get joint position upper limits.
dg::SignalTimeDependent< MatrixHomogeneous, sigtime_t > & positionsSOUT(const std::string &name)
dg::SignalTimeDependent< dg::Vector, sigtime_t > lowerJlSOUT
void signalRegistration(const SignalArray< int > &signals)
dg::SignalTimeDependent< MatrixHomogeneous, sigtime_t > & createPositionSignal(const std::string &, const std::string &)
const DataTpl< Scalar, Options, JointCollectionTpl >::SE3 & updateFramePlacement(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id)
TangentVectorType effortLimit
dg::SignalTimeDependent< dg::Vector, sigtime_t > & accelerationsSOUT(const std::string &name)
void addCommand(const std::string &name, command::Command *command)
DynamicPinocchio(const std::string &name)
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
dg::Vector & getUpperVelocityLimits(dg::Vector &res, const sigtime_t &) const
Get joint velocity upper limits.
SignalBase< int > & getSignal(const std::string &signalName)
virtual bool needUpdate(const Time &t) const
static void se3Action(const SE3Tpl< Scalar, Options > &m, const Eigen::MatrixBase< Mat > &iV, Eigen::MatrixBase< MatRet > const &jV)
dg::SignalTimeDependent< dg::Vector, sigtime_t > upperTlSOUT
dg::Vector & getPinocchioVel(dg::Vector &v, const sigtime_t &time)
dg::Vector & computeZmp(dg::Vector &res, const sigtime_t &time)
void signalDeregistration(const std::string &name)
ConfigVectorType upperPositionLimit
void cmd_createJacobianWorldSignal(const std::string &sig, const std::string &j)
dg::SignalPtr< dg::Vector, sigtime_t > jointAccelerationSIN
MatrixHomogeneous & computeGenericPosition(const bool isFrame, const int jointId, MatrixHomogeneous &res, const sigtime_t &time)
dg::SignalTimeDependent< dg::Vector, sigtime_t > AngularMomentumSOUT
dg::SignalTimeDependent< dg::Vector, sigtime_t > dynamicDriftSOUT
dg::SignalTimeDependent< Dummy, sigtime_t > jacobiansSINTERN
void cmd_createAccelerationSignal(const std::string &sig, const std::string &j)
dg::Vector & computeAngularMomentum(dg::Vector &res, const sigtime_t &time)
dg::Matrix & computeInertia(dg::Matrix &res, const sigtime_t &time)