Go to the documentation of this file.
13 #include <dynamic-graph/factory.h>
16 #include <boost/function.hpp>
17 #include <boost/numeric/conversion/cast.hpp>
26 #include "../tools/type-name-helper.hh"
28 namespace dg = ::dynamicgraph;
34 #define ADD_COMMAND(name, def) commandMap.insert(std::make_pair(name, def))
38 template <
typename TypeIn,
typename TypeOut>
51 "Undocumented unary operator\n"
68 for (std::size_t
i = 0;
i <
idxs.size(); ++
i) {
71 assert((nr >= 0) && (
R + nr <=
m.size()));
72 res.segment(
r, nr) =
m.segment(
R, nr);
78 typedef std::pair<Vector::Index, Vector::Index>
segment_t;
100 "size_type (min)",
"size_type (max)");
105 "size_type (min)",
"size_type (max)");
125 boost::function<void(
const int &)>
callback =
128 "size_type (index)");
132 std::string docString(
133 "Select a component of a vector\n"
143 assert((imin <= imax) && (imax <=
m.rows()));
144 assert((jmin <= jmax) && (jmax <=
m.cols()));
145 res.resize(imax - imin, jmax - jmin);
147 for (
size_type j = jmin; j < jmax; ++j)
res(
i - imin, j - jmin) =
m(
i, j);
177 doc =
docCommandVoid2(
"Set the bound on cols [m,M[.",
"size_type (min)",
187 assert((imin <= imax) && (imax <=
m.rows()));
188 assert(jcol <
m.cols());
190 res.resize(imax - imin);
209 boost::function<void(
const size_type &)> selectCol =
216 doc =
docCommandVoid1(
"Select the col to copy.",
"size_type (col index)");
229 res =
r.asDiagonal();
257 template <
typename matrixgen>
270 std::string docString(
271 "Computes the norm of a vector\n"
296 res.head<3>() =
M.translation();
297 res.tail<3>() =
r.angle() *
r.axis();
313 assert(
v.size() >= 6);
314 res.translation() =
v.head<3>();
315 double theta =
v.tail<3>().norm();
317 res.linear() = Eigen::AngleAxisd(theta,
v.tail<3>() / theta).matrix();
319 res.linear().setIdentity();
326 Mres.translation() = vect.head<3>();
327 Mres.linear().row(0) = vect.segment(3, 3);
328 Mres.linear().row(1) = vect.segment(6, 3);
329 Mres.linear().row(2) = vect.segment(9, 3);
337 res.head<3>() =
M.translation();
338 res.segment(3, 3) =
M.linear().row(0);
339 res.segment(6, 3) =
M.linear().row(1);
340 res.segment(9, 3) =
M.linear().row(2);
347 Mres.translation() = vect.head<3>();
356 res.head<3>() =
M.translation();
357 Eigen::Map<VectorQuaternion>
q(
res.tail<4>().data());
369 for (std::size_t
i = 0;
i < 3; ++
i)
res(
i) =
t(
i);
370 for (std::size_t
i = 0;
i < 3; ++
i)
res(
i + 3) =
r(
i);
378 for (std::size_t
i = 0;
i < 3; ++
i)
r(
i) = vect(
i + 3);
380 Eigen::AngleAxisd(
r(1), Eigen::Vector3d::UnitY()) *
381 Eigen::AngleAxisd(
r(0), Eigen::Vector3d::UnitX()))
385 for (std::size_t
i = 0;
i < 3; ++
i)
t(
i) = vect(
i);
388 Mres = Eigen::Translation3d(
t) *
R;
395 for (std::size_t
i = 0;
i < 3; ++
i)
r(
i) = vect(
i + 3);
397 Eigen::AngleAxisd(
r(1), Eigen::Vector3d::UnitY()) *
398 Eigen::AngleAxisd(
r(0), Eigen::Vector3d::UnitX()))
404 for (std::size_t
i = 0;
i < 3; ++
i) {
405 vectres(
i) = vect(
i);
406 vectres(
i + 3) = rrot.angle() * rrot.axis()(
i);
426 Eigen::Vector3d _t =
M.translation();
429 Tx << 0, -_t(2), _t(1), _t(2), 0, -_t(0), -_t(1), _t(0), 0;
433 res.block<3, 3>(0, 0) =
R;
434 res.block<3, 3>(0, 3) = sk;
435 res.block<3, 3>(3, 0) = Eigen::Matrix3d::Zero();
436 res.block<3, 3>(3, 3) =
R;
450 res =
M.translation();
456 res = (Eigen::AngleAxisd(
r(2), Eigen::Vector3d::UnitZ()) *
457 Eigen::AngleAxisd(
r(1), Eigen::Vector3d::UnitY()) *
458 Eigen::AngleAxisd(
r(0), Eigen::Vector3d::UnitX()))
465 res = (
r.eulerAngles(2, 1, 0)).reverse();
470 :
public UnaryOpHeader<VectorRollPitchYaw, VectorQuaternion> {
472 res = (Eigen::AngleAxisd(
r(2), Eigen::Vector3d::UnitZ()) *
473 Eigen::AngleAxisd(
r(1), Eigen::Vector3d::UnitY()) *
474 Eigen::AngleAxisd(
r(0), Eigen::Vector3d::UnitX()))
480 :
public UnaryOpHeader<VectorQuaternion, VectorRollPitchYaw> {
482 res = (
r.toRotationMatrix().eulerAngles(2, 1, 0)).reverse();
489 res =
r.toRotationMatrix();
513 template <
typename TypeIn1,
typename TypeIn2,
typename TypeOut>
530 "Undocumented binary operator\n"
556 template <
typename F,
typename E>
566 res =
f.matrix() * e;
587 template <
typename T>
597 :
public BinaryOpHeader<dynamicgraph::Vector, dynamicgraph::Vector,
598 dynamicgraph::Vector> {
605 assert((v1max >= v1min) && (v1.size() >= v1max));
606 assert((v2max >= v2min) && (v2.size() >= v2max));
608 const size_type v1size = v1max - v1min, v2size = v2max - v2min;
609 res.resize(v1size + v2size);
611 res(
i) = v1(
i + v1min);
614 res(v1size +
i) = v2(
i + v2min);
641 "size_type (imin)",
"size_type (imax)")));
646 "size_type (imin)",
"size_type (imax)")));
653 :
public BinaryOpHeader<dynamicgraph::Matrix, dynamicgraph::Vector,
665 :
public BinaryOpHeader<dynamicgraph::Vector, dynamicgraph::Matrix,
666 dynamicgraph::Vector> {
673 sotDEBUG(15) <<
"Size: " << nconv <<
"x" << nsig << std::endl;
674 if (nconv > f2.cols())
return;
679 for (MemoryType::const_iterator iter = f1.begin(); iter != f1.end();
682 sotDEBUG(45) <<
"Sig" << j <<
": " << s_tau;
683 if (s_tau.size() != nsig)
return;
685 res(
i) += f2(
i, j) * s_tau(
i);
693 memory.push_front(v1);
694 while ((
Vector::Index)memory.size() > m2.cols()) memory.pop_back();
695 convolution(memory, m2,
res);
701 template <
typename T>
709 "Comparison of inputs:\n"
711 Base::nameTypeIn1() +
715 Base::nameTypeIn2() +
719 Base::nameTypeOut() +
722 " sout = ( sin1 < sin2 )\n");
726 template <
typename T1,
typename T2 = T1>
731 res = (
a.array() <=
b.array()).any();
732 else if (equal && !any)
733 res = (
a.array() <=
b.array()).all();
734 else if (!equal && any)
735 res = (
a.array() <
b.array()).any();
736 else if (!equal && !any)
737 res = (
a.array() <
b.array()).all();
742 "Comparison of inputs:\n"
744 Base::nameTypeIn1() +
748 Base::nameTypeIn2() +
752 Base::nameTypeOut() +
755 " sout = ( sin1 < sin2 ).op()\n") +
758 " where op is either any (default) or all. The "
759 "comparison can be made <=.\n");
785 template <
typename T>
789 inline void operator()(
const T &v1,
const T &v2, T &res)
const {
815 return std::string(
"Weighted Combination of inputs : \n - gain{1|2} gain.");
824 template <
typename Tin,
typename Tout,
typename Time>
828 template <
typename Tin,
typename Tout,
typename Time>
833 template <
typename TypeIn,
typename TypeOut>
843 template <
typename Op>
848 "Undocumented variadic operator\n"
870 inline void operator()(
const std::vector<const Vector *> &vs,
873 for (std::size_t
i = 0;
i <
idxs.size(); ++
i) {
875 if (
s.sigIdx >= vs.size())
876 throw std::invalid_argument(
"Index out of range in VectorMix");
877 res.segment(
s.index,
s.size) = *vs[
s.sigIdx];
896 commandMap.insert(std::make_pair(
898 makeCommandVoid3<Base, size_type, size_type, sigtime_t>(
901 "size_type (signal index >= 1)",
902 "size_type (index)",
"size_type (size)"))));
907 template <
typename T>
915 inline void operator()(
const std::vector<const T *> &vs, T &res)
const {
916 assert(vs.size() == (std::size_t)coeffs.size());
917 if (vs.size() == 0)
return;
918 res = coeffs[0] * (*vs[0]);
919 for (std::size_t
i = 1;
i < vs.size(); ++
i)
res += coeffs[
i] * (*vs[
i]);
924 throw std::invalid_argument(
"Invalid coefficient size.");
928 coeffs = Vector::Ones(
n);
937 return "Linear combination of inputs\n"
944 " sout = sum ([coeffs[i] * sin[i] for i in range(n) ])\n"
945 " Coefficients are set by commands, default value is 1.\n";
950 template <
typename T>
954 inline void operator()(
const std::vector<const T *> &vs, T &res)
const {
959 for (std::size_t
i = 1;
i < vs.size(); ++
i)
res *= *vs[
i];
975 const std::vector<const MatrixHomogeneous *> &vs,
981 for (std::size_t
i = 1;
i < vs.size(); ++
i)
res =
res * *vs[
i];
986 const std::vector<const Vector *> &vs,
Vector &res)
const {
991 for (std::size_t
i = 1;
i < vs.size(); ++
i)
res.array() *= vs[
i]->array();
996 template <
size_type operation>
1000 inline void operator()(
const std::vector<const bool *> &vs,
bool &res)
const {
1004 if (vs.size() == 0)
return;
1006 for (std::size_t
i = 1;
i < vs.size(); ++
i)
switch (operation) {
UnaryOpHeader< matrixgen, matrixgen >::Tout Tout
void operator()(const dynamicgraph::Matrix &R, const dynamicgraph::Vector &t, MatrixHomogeneous &H) const
static std::string getTypeInName(void)
void operator()(const Tin &m, double &res) const
VariadicOp< BoolOp > Base
void operator()(const MatrixHomogeneous &M, MatrixTwist &res)
void initialize(Base *ent, Entity::CommandMap_t &)
Eigen::Quaternion< double > SOT_CORE_EXPORT VectorQuaternion
VariadicOp< Multiplier > Base
void operator()(const MatrixHomogeneous &M, dg::Vector &res)
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
void initialize(Base *ent, Entity::CommandMap_t &commandMap)
Multiplier_FxE__E< MatrixTwist, dynamicgraph::Vector > Multiplier_matrixTwist_vector
Eigen::Transform< double, 3, Eigen::Affine > SOT_CORE_EXPORT MatrixHomogeneous
void updateSignalNumber(const size_type &n)
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
void operator()(const MatrixHomogeneous &M, Vector &res)
void operator()(const T &a, const T &b, bool &res) const
void operator()(const VectorUTheta &r, VectorQuaternion &res)
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
void selectCol(const size_type &m)
void operator()(const Matrix &m, Matrix &res) const
Multiplier_FxE__E< double, dynamicgraph::Vector > Multiplier_double_vector
void operator()(const Eigen::Matrix< double, 4, 4 > &M, MatrixHomogeneous &res)
std::string getDocString() const
std::string getDocString() const
void operator()(const VectorQuaternion &r, VectorRollPitchYaw &res)
void setSignalNumber(const size_type &n)
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres)
Multiplier_FxE__E< MatrixHomogeneous, dynamicgraph::Vector > Multiplier_matrixHomo_vector
void operator()(const std::vector< const bool * > &vs, bool &res) const
void setBoundsCol(const size_type &m, const size_type &M)
void operator()(const VectorRollPitchYaw &r, VectorQuaternion &res)
void addSelec(const size_type &sigIdx, const size_type &i, const size_type &s)
void operator()(const Tin &m, Tout &res) const
UnaryOpHeader< matrixgen, matrixgen >::Tin Tin
DirectGetter< E, T > * makeDirectGetter(E &entity, T *ptr, const std::string &docString)
void operator()(const std::vector< const T * > &vs, T &res) const
void operator()(const dynamicgraph::Vector &v1, const dynamicgraph::Vector &v2, dynamicgraph::Vector &res) const
segment_t(Vector::Index i, Vector::Index s, std::size_t sig)
Eigen::Vector3d SOT_CORE_EXPORT VectorRollPitchYaw
void operator()(const Tin &m, Tout &res) const
std::string docCommandVoid1(const std::string &doc, const std::string &type)
void operator()(const dg::Vector &m, double &res) const
static std::string getTypeOutName(void)
void resize(const size_type &r, const size_type &c)
void setBounds(const size_type &m, const size_type &M)
void operator()(const VectorQuaternion &r, MatrixRotation &res)
void operator()(const dg::Vector &vect, dg::Vector &vectres)
VariadicOp< VectorMix > Base
void operator()(const MatrixRotation &r, VectorUTheta &res)
Eigen::AngleAxis< double > SOT_CORE_EXPORT VectorUTheta
std::string getDocString() const
void operator()(const F &f, const E &e, E &res) const
std::map< const std::string, command::Command * > CommandMap_t
std::string docCommandVoid3(const std::string &doc, const std::string &type1, const std::string &type2, const std::string &type3)
void operator()(const T &v1, const T &v2, T &r) const
void setBoundsRow(const size_type &m, const size_type &M)
std::vector< segment_t > segments_t
std::string docDirectSetter(const std::string &name, const std::string &type)
void operator()(const MatrixHomogeneous &M, dg::Matrix &res)
VariadicOp< AdderVariadic > Base
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
void operator()(const std::vector< const T * > &vs, T &res) const
void operator()(const Tin &m, Tout &res) const
void selec2(const size_type &m, const size_type M)
void operator()(const dg::Vector &v, MatrixHomogeneous &res)
void toRotationMatrix(const Eigen::MatrixBase< Vector3 > &axis, const Scalar &cos_value, const Scalar &sin_value, const Eigen::MatrixBase< Matrix3 > &res)
void operator()(const dynamicgraph::Vector &v1, const dynamicgraph::Matrix &m2, dynamicgraph::Vector &res)
CommandVoid2< E, T1, T2 > * makeCommandVoid2(E &entity, boost::function< void(const T1 &, const T2 &)> function, const std::string &docString)
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
std::string docCommandVoid2(const std::string &doc, const std::string &type1, const std::string &type2)
void setIdentity(T &res) const
Eigen::Matrix< double, 6, 6 > SOT_CORE_EXPORT MatrixTwist
void addBounds(const size_type &m, const size_type &M)
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
std::string docDirectGetter(const std::string &name, const std::string &type)
void operator()(const T1 &a, const T2 &b, bool &res) const
std::vector< segment_t > segments_t
void initialize(Base *ent, Entity::CommandMap_t &)
void operator()(const MatrixRotation &r, VectorQuaternion &res)
void operator()(const Tin &m, Vector &res) const
void operator()(const std::vector< const Vector * > &vs, Vector &res) const
void operator()(const dg::Vector &r, dg::Matrix &res)
void operator()(const MatrixRotation &r, VectorRollPitchYaw &res)
std::string getDocString() const
std::pair< Vector::Index, Vector::Index > segment_t
void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres)
void selec1(const size_type &m, const size_type M)
void convolution(const MemoryType &f1, const dynamicgraph::Matrix &f2, dynamicgraph::Vector &res)
Eigen::Matrix< double, 3, 3 > SOT_CORE_EXPORT MatrixRotation
void operator()(const MatrixHomogeneous &M, Vector &res)
void setBoundsRow(const size_type &m, const size_type &M)
DirectSetter< E, T > * makeDirectSetter(E &entity, T *ptr, const std::string &docString)
std::deque< dynamicgraph::Vector > MemoryType
std::string getDocString() const
Signal< dynamicgraph::Matrix, sigtime_t > sig("matrix")
static std::string typeName()
Multiplier_FxE__E< dynamicgraph::Matrix, dynamicgraph::Vector > Multiplier_matrix_vector
void operator()(const VectorRollPitchYaw &r, MatrixRotation &res)
#define ADD_COMMAND(name, def)
void operator()(const Tin &m, Tout &res) const
void operator()(const MatrixHomogeneous &M, dg::Vector &res)
void addSpecificCommands(Entity &ent, Entity::CommandMap_t &commandMap)
void setCoeffs(const Vector &c)
void operator()(const T &v1, const T &v2, T &res) const
std::string getDocString() const
CommandVoid1< E, T > * makeCommandVoid1(E &entity, boost::function< void(const T &)> function, const std::string &docString)
void operator()(const Matrix &M, Vector &res)
void operator()(const MatrixHomogeneous &M, dg::Vector &res)
void operator()(const MatrixHomogeneous &M, MatrixRotation &res)
size_type getSignalNumber() const
void setIndex(const size_type &m)
void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres)
void operator()(const Tin &m, Tout &res) const
sot-core
Author(s): Olivier Stasse, ostasse@laas.fr
autogenerated on Tue Oct 24 2023 02:26:31