Skip to content
Snippets Groups Projects
Commit 27b4edc1 authored by Olivier Stasse's avatar Olivier Stasse
Browse files

Fix dg namespace pb.

parent 3a2714c3
No related branches found
No related tags found
No related merge requests found
Showing
with 131 additions and 152 deletions
Subproject commit 9e21ae2222fdb51dccd1320bb7208f73259b0c73
Subproject commit c333a88decb3e4c0a86947bc6c7f072dc5c5df20
......@@ -35,17 +35,16 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
class SOTBINARYINTTOUINT_EXPORT BinaryIntToUint : public dg::Entity {
class SOTBINARYINTTOUINT_EXPORT BinaryIntToUint : public dynamicgraph::Entity {
public:
static const std::string CLASS_NAME;
virtual const std::string &getClassName(void) const { return CLASS_NAME; }
/* --- SIGNALS ------------------------------------------------------------ */
public:
dg::SignalPtr<int, int> binaryIntSIN;
dg::SignalTimeDependent<unsigned, int> binaryUintSOUT;
dynamicgraph::SignalPtr<int, int> binaryIntSIN;
dynamicgraph::SignalTimeDependent<unsigned, int> binaryUintSOUT;
public:
BinaryIntToUint(const std::string &name);
......
......@@ -15,7 +15,6 @@
/* Matrix */
#include <dynamic-graph/linear-algebra.h>
namespace dg = dynamicgraph;
/* SOT */
#include <dynamic-graph/all-signals.h>
......@@ -39,24 +38,23 @@ namespace dg = dynamicgraph;
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/* --------------------------------------------------------------------- */
/* --- CLASS ----------------------------------------------------------- */
/* --------------------------------------------------------------------- */
class SOTCLAMPWORKSPACE_EXPORT ClampWorkspace : public dg::Entity {
class SOTCLAMPWORKSPACE_EXPORT ClampWorkspace : public dynamicgraph::Entity {
public:
static const std::string CLASS_NAME;
virtual const std::string &getClassName(void) const { return CLASS_NAME; }
/* --- SIGNALS ------------------------------------------------------------ */
public:
dg::SignalPtr<MatrixHomogeneous, int> positionrefSIN;
dg::SignalPtr<MatrixHomogeneous, int> positionSIN;
dg::SignalTimeDependent<dg::Matrix, int> alphaSOUT;
dg::SignalTimeDependent<dg::Matrix, int> alphabarSOUT;
dg::SignalTimeDependent<MatrixHomogeneous, int> handrefSOUT;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionrefSIN;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionSIN;
dynamicgraph::SignalTimeDependent<dynamicgraph::Matrix, int> alphaSOUT;
dynamicgraph::SignalTimeDependent<dynamicgraph::Matrix, int> alphabarSOUT;
dynamicgraph::SignalTimeDependent<MatrixHomogeneous, int> handrefSOUT;
public:
ClampWorkspace(const std::string &name);
......@@ -64,8 +62,8 @@ public:
void update(int time);
virtual dg::Matrix &computeOutput(dg::Matrix &res, int time);
virtual dg::Matrix &computeOutputBar(dg::Matrix &res, int time);
virtual dynamicgraph::Matrix &computeOutput(dynamicgraph::Matrix &res, int time);
virtual dynamicgraph::Matrix &computeOutputBar(dynamicgraph::Matrix &res, int time);
virtual MatrixHomogeneous &computeRef(MatrixHomogeneous &res, int time);
virtual void display(std::ostream &) const;
......@@ -73,10 +71,10 @@ public:
private:
int timeUpdate;
dg::Matrix alpha;
dg::Matrix alphabar;
dynamicgraph::Matrix alpha;
dynamicgraph::Matrix alphabar;
MatrixHomogeneous prefMp;
dg::Vector pd;
dynamicgraph::Vector pd;
MatrixRotation Rd;
MatrixHomogeneous handref;
......
......@@ -16,7 +16,6 @@
/* Matrix */
#include <dynamic-graph/linear-algebra.h>
namespace dg = dynamicgraph;
/* SOT */
#include <dynamic-graph/all-signals.h>
......@@ -39,19 +38,17 @@ namespace dg = dynamicgraph;
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/* --------------------------------------------------------------------- */
/* --- CLASS ----------------------------------------------------------- */
/* --------------------------------------------------------------------- */
class SOTCOMFREEZER_EXPORT CoMFreezer : public dg::Entity {
class SOTCOMFREEZER_EXPORT CoMFreezer : public dynamicgraph::Entity {
public:
static const std::string CLASS_NAME;
virtual const std::string &getClassName() const { return CLASS_NAME; }
private:
dg::Vector m_lastCoM;
dynamicgraph::Vector m_lastCoM;
bool m_previousPGInProcess;
int m_lastStopTime;
......@@ -60,12 +57,12 @@ public: /* --- CONSTRUCTION --- */
virtual ~CoMFreezer(void);
public: /* --- SIGNAL --- */
dg::SignalPtr<dg::Vector, int> CoMRefSIN;
dg::SignalPtr<unsigned, int> PGInProcessSIN;
dg::SignalTimeDependent<dg::Vector, int> freezedCoMSOUT;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> CoMRefSIN;
dynamicgraph::SignalPtr<unsigned, int> PGInProcessSIN;
dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> freezedCoMSOUT;
public: /* --- FUNCTION --- */
dg::Vector &computeFreezedCoM(dg::Vector &freezedCoM, const int &time);
dynamicgraph::Vector &computeFreezedCoM(dynamicgraph::Vector &freezedCoM, const int &time);
public: /* --- PARAMS --- */
virtual void display(std::ostream &os) const;
......
......@@ -16,7 +16,6 @@
/* Matrix */
#include <dynamic-graph/linear-algebra.h>
namespace dg = dynamicgraph;
/* SOT */
#include <dynamic-graph/entity.h>
......@@ -40,7 +39,6 @@ namespace dg = dynamicgraph;
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/* --------------------------------------------------------------------- */
/* --- CLASS ----------------------------------------------------------- */
......@@ -70,14 +68,14 @@ protected:
double _dimension;
public: /* --- SIGNALS --- */
SignalPtr<dg::Matrix, int> matrixASIN;
SignalPtr<dg::Vector, int> accelerationSIN;
SignalPtr<dg::Vector, int> gravitySIN;
SignalTimeDependent<dg::Vector, int> controlSOUT;
SignalPtr<dynamicgraph::Matrix, int> matrixASIN;
SignalPtr<dynamicgraph::Vector, int> accelerationSIN;
SignalPtr<dynamicgraph::Vector, int> gravitySIN;
SignalTimeDependent<dynamicgraph::Vector, int> controlSOUT;
protected:
double &setsize(int dimension);
dg::Vector &computeControl(dg::Vector &tau, int t);
dynamicgraph::Vector &computeControl(dynamicgraph::Vector &tau, int t);
};
} // namespace sot
......
......@@ -16,7 +16,6 @@
/* Matrix */
#include <dynamic-graph/linear-algebra.h>
namespace dg = dynamicgraph;
/* SOT */
#include <dynamic-graph/entity.h>
......@@ -67,22 +66,22 @@ protected:
double TimeStep;
public: /* --- SIGNALS --- */
SignalPtr<dg::Vector, int> KpSIN;
SignalPtr<dg::Vector, int> KdSIN;
SignalPtr<dg::Vector, int> positionSIN;
SignalPtr<dg::Vector, int> desiredpositionSIN;
SignalPtr<dg::Vector, int> velocitySIN;
SignalPtr<dg::Vector, int> desiredvelocitySIN;
SignalTimeDependent<dg::Vector, int> controlSOUT;
SignalTimeDependent<dg::Vector, int> positionErrorSOUT;
SignalTimeDependent<dg::Vector, int> velocityErrorSOUT;
SignalPtr<dynamicgraph::Vector, int> KpSIN;
SignalPtr<dynamicgraph::Vector, int> KdSIN;
SignalPtr<dynamicgraph::Vector, int> positionSIN;
SignalPtr<dynamicgraph::Vector, int> desiredpositionSIN;
SignalPtr<dynamicgraph::Vector, int> velocitySIN;
SignalPtr<dynamicgraph::Vector, int> desiredvelocitySIN;
SignalTimeDependent<dynamicgraph::Vector, int> controlSOUT;
SignalTimeDependent<dynamicgraph::Vector, int> positionErrorSOUT;
SignalTimeDependent<dynamicgraph::Vector, int> velocityErrorSOUT;
protected:
dg::Vector &computeControl(dg::Vector &tau, int t);
dg::Vector position_error_;
dg::Vector velocity_error_;
dg::Vector &getPositionError(dg::Vector &position_error, int t);
dg::Vector &getVelocityError(dg::Vector &velocity_error, int t);
dynamicgraph::Vector &computeControl(dynamicgraph::Vector &tau, int t);
dynamicgraph::Vector position_error_;
dynamicgraph::Vector velocity_error_;
dynamicgraph::Vector &getPositionError(dynamicgraph::Vector &position_error, int t);
dynamicgraph::Vector &getVelocityError(dynamicgraph::Vector &velocity_error, int t);
};
} // namespace sot
......
......@@ -33,7 +33,6 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
#ifdef WIN32
#define DECLARE_SPECIFICATION(className, sotSigType) \
......@@ -47,8 +46,8 @@ namespace dg = dynamicgraph;
#endif
DECLARE_SPECIFICATION(DerivatorDouble, double)
DECLARE_SPECIFICATION(DerivatorVector, dg::Vector)
DECLARE_SPECIFICATION(DerivatorMatrix, dg::Matrix)
DECLARE_SPECIFICATION(DerivatorVector, dynamicgraph::Vector)
DECLARE_SPECIFICATION(DerivatorMatrix, dynamicgraph::Matrix)
DECLARE_SPECIFICATION(DerivatorVectorQuaternion, VectorQuaternion)
} /* namespace sot */
} /* namespace dynamicgraph */
......
......@@ -29,13 +29,12 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/* --------------------------------------------------------------------- */
/* --- CLASS ----------------------------------------------------------- */
/* --------------------------------------------------------------------- */
template <class T> class Derivator : public dg::Entity {
template <class T> class Derivator : public dynamicgraph::Entity {
DYNAMIC_GRAPH_ENTITY_DECL();
protected:
......@@ -48,7 +47,7 @@ public: /* --- CONSTRUCTION --- */
static std::string getTypeName(void) { return "Unknown"; }
Derivator(const std::string &name)
: dg::Entity(name), memory(), initialized(false),
: dynamicgraph::Entity(name), memory(), initialized(false),
timestep(TIMESTEP_DEFAULT),
SIN(NULL, "sotDerivator<" + getTypeName() + ">(" + name + ")::input(" +
getTypeName() + ")::sin"),
......@@ -65,9 +64,9 @@ public: /* --- CONSTRUCTION --- */
virtual ~Derivator(void){};
public: /* --- SIGNAL --- */
dg::SignalPtr<T, int> SIN;
dg::SignalTimeDependent<T, int> SOUT;
dg::Signal<double, int> timestepSIN;
dynamicgraph::SignalPtr<T, int> SIN;
dynamicgraph::SignalTimeDependent<T, int> SOUT;
dynamicgraph::Signal<double, int> timestepSIN;
protected:
T &computeDerivation(T &res, int time) {
......
......@@ -17,7 +17,7 @@
/* -- MaaL --- */
#include <dynamic-graph/linear-algebra.h>
namespace dg = dynamicgraph;
/* SOT */
#include "sot/core/api.hh"
#include "sot/core/periodic-call.hh"
......@@ -55,10 +55,10 @@ public:
};
protected:
dg::Vector state_;
dg::Vector velocity_;
dynamicgraph::Vector state_;
dynamicgraph::Vector velocity_;
bool sanityCheck_;
dg::Vector vel_control_;
dynamicgraph::Vector vel_control_;
ControlInput controlInputType_;
bool withForceSignals[4];
PeriodicCall periodicCallBefore_;
......@@ -81,9 +81,9 @@ public:
virtual ~Device();
virtual void setStateSize(const unsigned int &size);
virtual void setState(const dg::Vector &st);
virtual void setState(const dynamicgraph::Vector &st);
void setVelocitySize(const unsigned int &size);
virtual void setVelocity(const dg::Vector &vel);
virtual void setVelocity(const dynamicgraph::Vector &vel);
virtual void setSecondOrderIntegration();
virtual void setNoIntegration();
virtual void setControlInputType(const std::string &cit);
......@@ -107,20 +107,20 @@ public: /* --- DISPLAY --- */
}
public: /* --- SIGNALS --- */
dynamicgraph::SignalPtr<dg::Vector, int> controlSIN;
dynamicgraph::SignalPtr<dg::Vector, int> attitudeSIN;
dynamicgraph::SignalPtr<dg::Vector, int> zmpSIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> controlSIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> attitudeSIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> zmpSIN;
/// \name Device current state.
/// \{
dynamicgraph::Signal<dg::Vector, int> stateSOUT;
dynamicgraph::Signal<dg::Vector, int> velocitySOUT;
dynamicgraph::Signal<dynamicgraph::Vector, int> stateSOUT;
dynamicgraph::Signal<dynamicgraph::Vector, int> velocitySOUT;
dynamicgraph::Signal<MatrixRotation, int> attitudeSOUT;
/*! \brief The current state of the robot from the command viewpoint. */
dynamicgraph::Signal<dg::Vector, int> motorcontrolSOUT;
dynamicgraph::Signal<dg::Vector, int> previousControlSOUT;
dynamicgraph::Signal<dynamicgraph::Vector, int> motorcontrolSOUT;
dynamicgraph::Signal<dynamicgraph::Vector, int> previousControlSOUT;
/*! \brief The ZMP reference send by the previous controller. */
dynamicgraph::Signal<dg::Vector, int> ZMPPreviousControllerSOUT;
dynamicgraph::Signal<dynamicgraph::Vector, int> ZMPPreviousControllerSOUT;
/// \}
/// \name Real robot current state
......@@ -129,19 +129,19 @@ public: /* --- SIGNALS --- */
/// does *not* match the state control input signal.
/// \{
/// Motor positions
dynamicgraph::Signal<dg::Vector, int> robotState_;
dynamicgraph::Signal<dynamicgraph::Vector, int> robotState_;
/// Motor velocities
dynamicgraph::Signal<dg::Vector, int> robotVelocity_;
dynamicgraph::Signal<dynamicgraph::Vector, int> robotVelocity_;
/// The force torque sensors
dynamicgraph::Signal<dg::Vector, int> *forcesSOUT[4];
dynamicgraph::Signal<dynamicgraph::Vector, int> *forcesSOUT[4];
/// Motor torques
/// \todo why pseudo ?
dynamicgraph::Signal<dg::Vector, int> pseudoTorqueSOUT;
dynamicgraph::Signal<dynamicgraph::Vector, int> pseudoTorqueSOUT;
/// \}
protected:
/// Compute roll pitch yaw angles of freeflyer joint.
void integrateRollPitchYaw(dg::Vector &state, const dg::Vector &control,
void integrateRollPitchYaw(dynamicgraph::Vector &state, const dynamicgraph::Vector &control,
double dt);
/// Store Position of free flyer joint
MatrixHomogeneous ffPose_;
......@@ -164,13 +164,13 @@ protected:
const MatrixHomogeneous &freeFlyerPose() const;
public:
virtual void setRoot(const dg::Matrix &root);
virtual void setRoot(const dynamicgraph::Matrix &root);
virtual void setRoot(const MatrixHomogeneous &worldMwaist);
private:
// Intermediate variable to avoid dynamic allocation
dg::Vector forceZero6;
dynamicgraph::Vector forceZero6;
};
} // namespace sot
} // namespace dynamicgraph
......
......@@ -18,7 +18,6 @@
#include <dynamic-graph/signal-time-dependent.h>
#include <sot/core/config.hh>
namespace dg = ::dynamicgraph;
namespace dynamicgraph {
namespace sot {
......@@ -35,9 +34,9 @@ class SOT_CORE_DLLAPI ExpMovingAvg : public Entity {
DYNAMIC_GRAPH_ENTITY_DECL();
public:
SignalPtr<dg::Vector, int> updateSIN;
SignalPtr<dynamicgraph::Vector, int> updateSIN;
SignalTimeDependent<int, int> refresherSINTERN;
SignalTimeDependent<dg::Vector, int> averageSOUT;
SignalTimeDependent<dynamicgraph::Vector, int> averageSOUT;
public:
ExpMovingAvg(const std::string &n);
......@@ -46,9 +45,9 @@ public:
void setAlpha(const double &alpha_);
protected:
dg::Vector &update(dg::Vector &res, const int &inTime);
dynamicgraph::Vector &update(dynamicgraph::Vector &res, const int &inTime);
dg::Vector average;
dynamicgraph::Vector average;
double alpha;
bool init;
......
......@@ -38,7 +38,6 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/*!
\class Feature1D
\brief Simple test: the task is defined to be e_2 = .5 . e'.e, with
......@@ -65,10 +64,10 @@ public:
@{
*/
/*! \brief Input for the error. */
dg::SignalPtr<dg::Vector, int> errorSIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> errorSIN;
/*! \brief Input for the Jacobian. */
dg::SignalPtr<dg::Matrix, int> jacobianSIN;
dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> jacobianSIN;
/*! @} */
......@@ -99,10 +98,10 @@ public:
/*! \brief Compute the error between the desired value and the value itself.
*/
virtual dg::Vector &computeError(dg::Vector &res, int time);
virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
/*! \brief Compute the Jacobian of the value according to the robot state.. */
virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
/*! @} */
......
......@@ -38,7 +38,6 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/*!
\class FeatureJointLimits
......@@ -62,10 +61,10 @@ protected:
/* --- SIGNALS ------------------------------------------------------------ */
public:
dg::SignalPtr<dg::Vector, int> jointSIN;
dg::SignalPtr<dg::Vector, int> upperJlSIN;
dg::SignalPtr<dg::Vector, int> lowerJlSIN;
dg::SignalTimeDependent<dg::Vector, int> widthJlSINTERN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> jointSIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> upperJlSIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> lowerJlSIN;
dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> widthJlSINTERN;
using FeatureAbstract::selectionSIN;
......@@ -84,9 +83,9 @@ public:
virtual unsigned int &getDimension(unsigned int &dim, int time);
virtual dg::Vector &computeError(dg::Vector &res, int time);
virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
dg::Vector &computeWidthJl(dg::Vector &res, const int &time);
virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
dynamicgraph::Vector &computeWidthJl(dynamicgraph::Vector &res, const int &time);
/** Static Feature selection. */
inline static Flags selectActuated(void);
......
......@@ -38,7 +38,6 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/*!
\class FeatureLineDistance
......@@ -54,11 +53,11 @@ public:
protected:
/* --- SIGNALS ------------------------------------------------------------ */
public:
dg::SignalPtr<MatrixHomogeneous, int> positionSIN;
dg::SignalPtr<dg::Matrix, int> articularJacobianSIN;
dg::SignalPtr<dg::Vector, int> positionRefSIN;
dg::SignalPtr<dg::Vector, int> vectorSIN;
dg::SignalTimeDependent<dg::Vector, int> lineSOUT;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionSIN;
dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianSIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> positionRefSIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> vectorSIN;
dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> lineSOUT;
using FeatureAbstract::errorSOUT;
using FeatureAbstract::jacobianSOUT;
......@@ -76,9 +75,9 @@ public:
virtual unsigned int &getDimension(unsigned int &dim, int time);
virtual dg::Vector &computeError(dg::Vector &res, int time);
virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
dg::Vector &computeLineCoordinates(dg::Vector &cood, int time);
virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
dynamicgraph::Vector &computeLineCoordinates(dynamicgraph::Vector &cood, int time);
virtual void display(std::ostream &os) const;
};
......
......@@ -40,7 +40,6 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/*!
\class FeaturePoint6dRelative
......@@ -56,23 +55,23 @@ public:
virtual const std::string &getClassName(void) const { return CLASS_NAME; }
protected:
dg::Matrix L;
dynamicgraph::Matrix L;
/* --- SIGNALS ------------------------------------------------------------ */
public:
dg::SignalPtr<MatrixHomogeneous, int> positionReferenceSIN;
dg::SignalPtr<dg::Matrix, int> articularJacobianReferenceSIN;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionReferenceSIN;
dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianReferenceSIN;
/*! dg::Signals related to the computation of the derivative of
/*! dynamicgraph::Signals related to the computation of the derivative of
the error
@{ */
/*! dg::Signals giving the derivative of the input signals.
/*! dynamicgraph::Signals giving the derivative of the input signals.
@{*/
/*! Derivative of the relative position. */
dg::SignalPtr<MatrixHomogeneous, int> dotpositionSIN;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> dotpositionSIN;
/*! Derivative of the reference position. */
dg::SignalPtr<MatrixHomogeneous, int> dotpositionReferenceSIN;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> dotpositionReferenceSIN;
/*! @} */
using FeaturePoint6d::getReference;
......@@ -81,9 +80,9 @@ public:
FeaturePoint6dRelative(const std::string &name);
virtual ~FeaturePoint6dRelative(void) {}
virtual dg::Vector &computeError(dg::Vector &res, int time);
virtual dg::Vector &computeErrorDot(dg::Vector &res, int time);
virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, int time);
virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
virtual void display(std::ostream &os) const;
......
......@@ -40,7 +40,6 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/*!
\class FeaturePoint6d
......@@ -71,9 +70,9 @@ private:
/* --- SIGNALS ------------------------------------------------------------ */
public:
dg::SignalPtr<MatrixHomogeneous, int> positionSIN;
dg::SignalPtr<dg::Vector, int> velocitySIN;
dg::SignalPtr<dg::Matrix, int> articularJacobianSIN;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionSIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> velocitySIN;
dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianSIN;
using FeatureAbstract::errorSOUT;
using FeatureAbstract::jacobianSOUT;
......@@ -90,9 +89,9 @@ public:
virtual unsigned int &getDimension(unsigned int &dim, int time);
virtual dg::Vector &computeError(dg::Vector &res, int time);
virtual dg::Vector &computeErrordot(dg::Vector &res, int time);
virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
virtual dynamicgraph::Vector &computeErrordot(dynamicgraph::Vector &res, int time);
virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
/** Static Feature selection. */
inline static Flags selectX(void) { return FLAG_LINE_1; }
......
......@@ -24,7 +24,6 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/// Enum used to specify what difference operation is used in FeaturePose.
enum Representation_t { SE3Representation, R3xSO3Representation };
......@@ -71,23 +70,23 @@ public:
@{
*/
/// Input pose of <em>Joint A</em> wrt to world frame.
dg::SignalPtr<MatrixHomogeneous, int> oMja;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> oMja;
/// Input pose of <em>Frame A</em> wrt to <em>Joint A</em>.
dg::SignalPtr<MatrixHomogeneous, int> jaMfa;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> jaMfa;
/// Input pose of <em>Joint B</em> wrt to world frame.
dg::SignalPtr<MatrixHomogeneous, int> oMjb;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> oMjb;
/// Input pose of <em>Frame B</em> wrt to <em>Joint B</em>.
dg::SignalPtr<MatrixHomogeneous, int> jbMfb;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> jbMfb;
/// Jacobian of the input <em>Joint A</em>, expressed in <em>Joint A</em>
dg::SignalPtr<Matrix, int> jaJja;
dynamicgraph::SignalPtr<Matrix, int> jaJja;
/// Jacobian of the input <em>Joint B</em>, expressed in <em>Joint B</em>
dg::SignalPtr<Matrix, int> jbJjb;
dynamicgraph::SignalPtr<Matrix, int> jbJjb;
/// The desired pose of <em>Frame B</em> wrt to <em>Frame A</em>.
dg::SignalPtr<MatrixHomogeneous, int> faMfbDes;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> faMfbDes;
/// The desired velocity of <em>Frame B</em> wrt to <em>Frame A</em>. The
/// value is expressed in <em>Frame A</em>.
dg::SignalPtr<Vector, int> faNufafbDes;
dynamicgraph::SignalPtr<Vector, int> faNufafbDes;
/*! @} */
/*! \name Output signals
......@@ -121,21 +120,21 @@ public:
virtual unsigned int &getDimension(unsigned int &dim, int time);
/// Computes \f$ {}^oM^{-1}_{fa} {}^oM_{fb} \ominus {}^{fa}M^*_{fb} \f$
virtual dg::Vector &computeError(dg::Vector &res, int time);
virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
/// Computes \f$ \frac{\partial\ominus}{\partial b} X {}^{fa}\nu^*_{fafb} \f$.
/// There are two different cases, depending on the representation:
/// - R3xSO3Representation: \f$ X = \left( \begin{array}{cc} I_3 & [
/// {}^{fa}t_{fb} ] \\ 0_3 & {{}^{fa}R^*_{fb}}^T \end{array} \right) \f$
/// - SE3Representation: \f$ X = {{}^{fa}X^*_{fb}}^{-1} \f$ (see
/// pinocchio::SE3Base<Scalar,Options>::toActionMatrix)
virtual dg::Vector &computeErrorDot(dg::Vector &res, int time);
virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, int time);
/// Computes \f$ \frac{\partial\ominus}{\partial b} Y \left( {{}^{fb}X_{jb}}
/// {}^{jb}J_{jb} - {{}^{fb}X_{ja}} {}^{ja}J_{ja} \right) \f$. There are two
/// different cases, depending on the representation:
/// - R3xSO3Representation: \f$ Y = \left( \begin{array}{cc} {{}^{fa}R_{fb}} &
/// 0_3 \\ 0_3 & I_3 \end{array} \right) \f$
/// - SE3Representation: \f$ Y = I_6 \f$
virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
/** Static Feature selection. */
inline static Flags selectX(void) { return FLAG_LINE_1; }
......
......@@ -39,7 +39,7 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
class SOTFEATURETASK_EXPORT FeatureTask : public FeatureGeneric {
......
......@@ -39,7 +39,6 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/*!
\class FeatureVector3
......@@ -56,10 +55,10 @@ public:
protected:
/* --- SIGNALS ------------------------------------------------------------ */
public:
dg::SignalPtr<dg::Vector, int> vectorSIN;
dg::SignalPtr<MatrixHomogeneous, int> positionSIN;
dg::SignalPtr<dg::Matrix, int> articularJacobianSIN;
dg::SignalPtr<dg::Vector, int> positionRefSIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> vectorSIN;
dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionSIN;
dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianSIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> positionRefSIN;
using FeatureAbstract::errorSOUT;
using FeatureAbstract::jacobianSOUT;
......@@ -71,8 +70,8 @@ public:
virtual unsigned int &getDimension(unsigned int &dim, int time);
virtual dg::Vector &computeError(dg::Vector &res, int time);
virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
virtual void display(std::ostream &os) const;
};
......
......@@ -38,7 +38,6 @@
namespace dynamicgraph {
namespace sot {
namespace dg = dynamicgraph;
/*!
\class FeatureVisualPoint
......@@ -53,15 +52,15 @@ public:
virtual const std::string &getClassName(void) const { return CLASS_NAME; }
protected:
dg::Matrix L;
dynamicgraph::Matrix L;
/* --- SIGNALS ------------------------------------------------------------ */
public:
dg::SignalPtr<dg::Vector, int> xySIN;
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> xySIN;
/** FeatureVisualPoint depth (required to compute the interaction matrix)
* default Z = 1m. */
dg::SignalPtr<double, int> ZSIN;
dg::SignalPtr<dg::Matrix, int> articularJacobianSIN;
dynamicgraph::SignalPtr<double, int> ZSIN;
dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianSIN;
using FeatureAbstract::errorSOUT;
using FeatureAbstract::jacobianSOUT;
......@@ -75,8 +74,8 @@ public:
virtual unsigned int &getDimension(unsigned int &dim, int time);
virtual dg::Vector &computeError(dg::Vector &res, int time);
virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
/** Static Feature selection. */
inline static Flags selectX(void) { return FLAG_LINE_1; }
......
......@@ -21,7 +21,6 @@
#include <dynamic-graph/command-setter.h>
#include <dynamic-graph/entity.h>
namespace dg = dynamicgraph;
namespace dynamicgraph {
namespace sot {
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment