diff --git a/include/sot/core/clamp-workspace.hh b/include/sot/core/clamp-workspace.hh index 7b53a11d7..d1c2544c7 100644 --- a/include/sot/core/clamp-workspace.hh +++ b/include/sot/core/clamp-workspace.hh @@ -62,8 +62,10 @@ public: void update(int time); - virtual dynamicgraph::Matrix &computeOutput(dynamicgraph::Matrix &res, int time); - virtual dynamicgraph::Matrix &computeOutputBar(dynamicgraph::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; diff --git a/include/sot/core/com-freezer.hh b/include/sot/core/com-freezer.hh index 4621f6e25..ab58d8ddc 100644 --- a/include/sot/core/com-freezer.hh +++ b/include/sot/core/com-freezer.hh @@ -62,7 +62,8 @@ public: /* --- SIGNAL --- */ dynamicgraph::SignalTimeDependent freezedCoMSOUT; public: /* --- FUNCTION --- */ - dynamicgraph::Vector &computeFreezedCoM(dynamicgraph::Vector &freezedCoM, const int &time); + dynamicgraph::Vector &computeFreezedCoM(dynamicgraph::Vector &freezedCoM, + const int &time); public: /* --- PARAMS --- */ virtual void display(std::ostream &os) const; diff --git a/include/sot/core/control-gr.hh b/include/sot/core/control-gr.hh index c0ac928f6..9a8f14092 100644 --- a/include/sot/core/control-gr.hh +++ b/include/sot/core/control-gr.hh @@ -39,7 +39,6 @@ namespace dynamicgraph { namespace sot { - /* --------------------------------------------------------------------- */ /* --- CLASS ----------------------------------------------------------- */ /* --------------------------------------------------------------------- */ diff --git a/include/sot/core/control-pd.hh b/include/sot/core/control-pd.hh index 293300f51..31ad8056b 100644 --- a/include/sot/core/control-pd.hh +++ b/include/sot/core/control-pd.hh @@ -80,8 +80,10 @@ protected: 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); + dynamicgraph::Vector &getPositionError(dynamicgraph::Vector &position_error, + int t); + dynamicgraph::Vector &getVelocityError(dynamicgraph::Vector &velocity_error, + int t); }; } // namespace sot diff --git a/include/sot/core/device.hh b/include/sot/core/device.hh index 9cb5c266c..0b835dc3f 100644 --- a/include/sot/core/device.hh +++ b/include/sot/core/device.hh @@ -141,8 +141,8 @@ public: /* --- SIGNALS --- */ protected: /// Compute roll pitch yaw angles of freeflyer joint. - void integrateRollPitchYaw(dynamicgraph::Vector &state, const dynamicgraph::Vector &control, - double dt); + void integrateRollPitchYaw(dynamicgraph::Vector &state, + const dynamicgraph::Vector &control, double dt); /// Store Position of free flyer joint MatrixHomogeneous ffPose_; /// Compute the new position, from the current control. diff --git a/include/sot/core/exp-moving-avg.hh b/include/sot/core/exp-moving-avg.hh index 2ed1d4252..de48d5f38 100644 --- a/include/sot/core/exp-moving-avg.hh +++ b/include/sot/core/exp-moving-avg.hh @@ -18,7 +18,6 @@ #include #include - namespace dynamicgraph { namespace sot { diff --git a/include/sot/core/feature-1d.hh b/include/sot/core/feature-1d.hh index 23705f190..ee7808d97 100644 --- a/include/sot/core/feature-1d.hh +++ b/include/sot/core/feature-1d.hh @@ -98,10 +98,12 @@ public: /*! \brief Compute the error between the desired value and the value itself. */ - virtual dynamicgraph::Vector &computeError(dynamicgraph::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 dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time); + virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, + int time); /*! @} */ diff --git a/include/sot/core/feature-abstract.hh b/include/sot/core/feature-abstract.hh index 282ae07fb..06ca928df 100644 --- a/include/sot/core/feature-abstract.hh +++ b/include/sot/core/feature-abstract.hh @@ -136,20 +136,23 @@ public: \par[in] time: The time at which the error is computed. \return The vector res with the appropriate value. */ - virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time) = 0; + virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, + int time) = 0; /*! \brief Compute the Jacobian of the error according the robot state. \par[out] res: The matrix in which the error will be written. \return The matrix res with the appropriate values. */ - virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time) = 0; + virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, + int time) = 0; /// Callback for signal errordotSOUT /// /// Copy components of the input signal errordotSIN defined by selection /// flag selectionSIN. - virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, int time); + virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, + int time); /*! @} */ diff --git a/include/sot/core/feature-generic.hh b/include/sot/core/feature-generic.hh index 2d0e9e189..2f1d00672 100644 --- a/include/sot/core/feature-generic.hh +++ b/include/sot/core/feature-generic.hh @@ -109,10 +109,12 @@ public: /*! \brief Compute the error between the desired value and the value itself. */ - virtual dynamicgraph::Vector &computeError(dynamicgraph::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 dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time); + virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, + int time); /*! @} */ diff --git a/include/sot/core/feature-joint-limits.hh b/include/sot/core/feature-joint-limits.hh index 8a11cb1ed..7c670d61c 100644 --- a/include/sot/core/feature-joint-limits.hh +++ b/include/sot/core/feature-joint-limits.hh @@ -83,9 +83,12 @@ public: virtual unsigned int &getDimension(unsigned int &dim, 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); + 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); diff --git a/include/sot/core/feature-line-distance.hh b/include/sot/core/feature-line-distance.hh index c618cd9e9..6aa7002f1 100644 --- a/include/sot/core/feature-line-distance.hh +++ b/include/sot/core/feature-line-distance.hh @@ -75,9 +75,12 @@ public: virtual unsigned int &getDimension(unsigned int &dim, 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 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; }; diff --git a/include/sot/core/feature-point6d-relative.hh b/include/sot/core/feature-point6d-relative.hh index e1d073070..997ad917b 100644 --- a/include/sot/core/feature-point6d-relative.hh +++ b/include/sot/core/feature-point6d-relative.hh @@ -60,7 +60,8 @@ protected: /* --- SIGNALS ------------------------------------------------------------ */ public: dynamicgraph::SignalPtr positionReferenceSIN; - dynamicgraph::SignalPtr articularJacobianReferenceSIN; + dynamicgraph::SignalPtr + articularJacobianReferenceSIN; /*! dynamicgraph::Signals related to the computation of the derivative of the error @@ -80,9 +81,12 @@ public: FeaturePoint6dRelative(const std::string &name); virtual ~FeaturePoint6dRelative(void) {} - 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 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; diff --git a/include/sot/core/feature-point6d.hh b/include/sot/core/feature-point6d.hh index e2624f071..5df8c4efa 100644 --- a/include/sot/core/feature-point6d.hh +++ b/include/sot/core/feature-point6d.hh @@ -89,9 +89,12 @@ public: virtual unsigned int &getDimension(unsigned int &dim, 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 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; } diff --git a/include/sot/core/feature-pose.hh b/include/sot/core/feature-pose.hh index a55d84208..23b5a366b 100644 --- a/include/sot/core/feature-pose.hh +++ b/include/sot/core/feature-pose.hh @@ -120,21 +120,24 @@ public: virtual unsigned int &getDimension(unsigned int &dim, int time); /// Computes \f$ {}^oM^{-1}_{fa} {}^oM_{fb} \ominus {}^{fa}M^*_{fb} \f$ - virtual dynamicgraph::Vector &computeError(dynamicgraph::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::toActionMatrix) - virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::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 dynamicgraph::Matrix &computeJacobian(dynamicgraph::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; } @@ -160,10 +163,10 @@ private: /// \todo Intermediate variables for internal computations }; -template < typename T > +template Vector6d convertVelocity(const MatrixHomogeneous &M, - const MatrixHomogeneous &Mdes, - const Vector &faNufafbDes); + const MatrixHomogeneous &Mdes, + const Vector &faNufafbDes); #if __cplusplus >= 201103L extern template class SOT_CORE_DLLAPI FeaturePose; extern template class SOT_CORE_DLLAPI FeaturePose; diff --git a/include/sot/core/feature-pose.hxx b/include/sot/core/feature-pose.hxx index 500dd4ecd..7ba9f5070 100644 --- a/include/sot/core/feature-pose.hxx +++ b/include/sot/core/feature-pose.hxx @@ -41,7 +41,7 @@ template struct LG_t { typedef typename boost::mpl::if_c::type type; }; -} +} // namespace internal /* --------------------------------------------------------------------- */ /* --- CLASS ----------------------------------------------------------- */ @@ -104,11 +104,7 @@ FeaturePose::FeaturePose(const std::string &pointName) } template -FeaturePose::~FeaturePose() -{ -} - - +FeaturePose::~FeaturePose() {} /* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */ @@ -261,8 +257,8 @@ Vector &FeaturePose::computeError(Vector &error, int time) { // feature (R^3xSO(3) or SE(3)), in the right frame. template <> Vector6d convertVelocity(const MatrixHomogeneous &M, - const MatrixHomogeneous &Mdes, - const Vector &faNufafbDes) { + const MatrixHomogeneous &Mdes, + const Vector &faNufafbDes) { (void)M; MatrixTwist X; buildFrom(Mdes.inverse(Eigen::Affine), X); @@ -351,6 +347,5 @@ void FeaturePose::display(std::ostream &os) const { } } - -} -} +} // namespace sot +} // namespace dynamicgraph diff --git a/include/sot/core/feature-posture.hh b/include/sot/core/feature-posture.hh index dede94104..fe78576d5 100644 --- a/include/sot/core/feature-posture.hh +++ b/include/sot/core/feature-posture.hh @@ -53,7 +53,8 @@ class SOTFEATUREPOSTURE_EXPORT FeaturePosture : public FeatureAbstract { public: typedef dynamicgraph::SignalPtr signalIn_t; - typedef dynamicgraph::SignalTimeDependent signalOut_t; + typedef dynamicgraph::SignalTimeDependent + signalOut_t; DECLARE_NO_REFERENCE; @@ -65,7 +66,8 @@ public: protected: virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int); virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int); - virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, int time); + virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, + int time); signalIn_t state_; signalIn_t posture_; diff --git a/include/sot/core/feature-task.hh b/include/sot/core/feature-task.hh index d1f33f40a..d4f1912cd 100644 --- a/include/sot/core/feature-task.hh +++ b/include/sot/core/feature-task.hh @@ -40,7 +40,6 @@ namespace dynamicgraph { namespace sot { - class SOTFEATURETASK_EXPORT FeatureTask : public FeatureGeneric { public: diff --git a/include/sot/core/feature-vector3.hh b/include/sot/core/feature-vector3.hh index 43402f531..7ed5e5e75 100644 --- a/include/sot/core/feature-vector3.hh +++ b/include/sot/core/feature-vector3.hh @@ -70,8 +70,10 @@ public: virtual unsigned int &getDimension(unsigned int &dim, int time); - virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time); - virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::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; }; diff --git a/include/sot/core/feature-visual-point.hh b/include/sot/core/feature-visual-point.hh index ffdc37c5f..9212bf149 100644 --- a/include/sot/core/feature-visual-point.hh +++ b/include/sot/core/feature-visual-point.hh @@ -74,8 +74,10 @@ public: virtual unsigned int &getDimension(unsigned int &dim, int time); - virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time); - virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::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; } diff --git a/include/sot/core/fir-filter.hh b/include/sot/core/fir-filter.hh index 3e563b36e..4dc9db35b 100644 --- a/include/sot/core/fir-filter.hh +++ b/include/sot/core/fir-filter.hh @@ -21,7 +21,6 @@ #include #include - namespace dynamicgraph { namespace sot { diff --git a/include/sot/core/gradient-ascent.hh b/include/sot/core/gradient-ascent.hh index 8eff01ba5..40df988a4 100644 --- a/include/sot/core/gradient-ascent.hh +++ b/include/sot/core/gradient-ascent.hh @@ -18,7 +18,6 @@ #include #include - namespace dynamicgraph { namespace sot { diff --git a/include/sot/core/gripper-control.hh b/include/sot/core/gripper-control.hh index 61189295a..75fef519d 100644 --- a/include/sot/core/gripper-control.hh +++ b/include/sot/core/gripper-control.hh @@ -46,7 +46,6 @@ namespace dynamicgraph { namespace sot { - /*! \brief The goal of this entity is to ensure that the maximal torque will not * be exceeded during a grasping task. * If the maximal torque is reached, then the current position of the gripper is @@ -71,26 +70,29 @@ public: const dynamicgraph::Vector ¤tNormVel); //! \brief - dynamicgraph::Vector &computeDesiredPosition(const dynamicgraph::Vector ¤tPos, - const dynamicgraph::Vector &desiredPos, - const dynamicgraph::Vector &torques, - const dynamicgraph::Vector &torqueLimits, - dynamicgraph::Vector &referencePos); + dynamicgraph::Vector & + computeDesiredPosition(const dynamicgraph::Vector ¤tPos, + const dynamicgraph::Vector &desiredPos, + const dynamicgraph::Vector &torques, + const dynamicgraph::Vector &torqueLimits, + dynamicgraph::Vector &referencePos); /*! \brief select only some of the values of the vector fullsize, * based on the Flags vector. */ - static dynamicgraph::Vector &selector(const dynamicgraph::Vector &fullsize, const Flags &selec, - dynamicgraph::Vector &desPos); + static dynamicgraph::Vector &selector(const dynamicgraph::Vector &fullsize, + const Flags &selec, + dynamicgraph::Vector &desPos); }; /* --------------------------------------------------------------------- */ /* --- PLUGIN ---------------------------------------------------------- */ /* --------------------------------------------------------------------- */ -class SOTGRIPPERCONTROL_EXPORT GripperControlPlugin : public dynamicgraph::Entity, - public GripperControl { +class SOTGRIPPERCONTROL_EXPORT GripperControlPlugin + : public dynamicgraph::Entity, + public GripperControl { DYNAMIC_GRAPH_ENTITY_DECL(); public: @@ -113,14 +115,17 @@ public: /* --- SIGNAL --- */ /* --- INTERMEDIARY --- */ dynamicgraph::SignalPtr positionFullSizeSIN; - dynamicgraph::SignalTimeDependent positionReduceSOUT; + dynamicgraph::SignalTimeDependent + positionReduceSOUT; dynamicgraph::SignalPtr torqueFullSizeSIN; dynamicgraph::SignalTimeDependent torqueReduceSOUT; dynamicgraph::SignalPtr torqueLimitFullSizeSIN; - dynamicgraph::SignalTimeDependent torqueLimitReduceSOUT; + dynamicgraph::SignalTimeDependent + torqueLimitReduceSOUT; /* --- OUTPUTS --- */ - dynamicgraph::SignalTimeDependent desiredPositionSOUT; + dynamicgraph::SignalTimeDependent + desiredPositionSOUT; public: /* --- COMMANDLINE --- */ void initCommands(); diff --git a/include/sot/core/integrator-abstract-impl.hh b/include/sot/core/integrator-abstract-impl.hh index 25df9ee43..9054fecbe 100644 --- a/include/sot/core/integrator-abstract-impl.hh +++ b/include/sot/core/integrator-abstract-impl.hh @@ -46,7 +46,8 @@ namespace dynamicgraph { namespace sot { DECLARE_SPECIFICATION(IntegratorAbstractDouble, double, double) -DECLARE_SPECIFICATION(IntegratorAbstractVector, dynamicgraph::Vector, dynamicgraph::Matrix) +DECLARE_SPECIFICATION(IntegratorAbstractVector, dynamicgraph::Vector, + dynamicgraph::Matrix) } // namespace sot } // namespace dynamicgraph #endif // #ifndef __SOT_MAILBOX_HH diff --git a/include/sot/core/integrator-euler.hh b/include/sot/core/integrator-euler.hh index e808c9b31..3b55fdf24 100644 --- a/include/sot/core/integrator-euler.hh +++ b/include/sot/core/integrator-euler.hh @@ -151,8 +151,9 @@ public: sigT &derivative(sigT &res, int time) { if (outputMemory.size() < 2) - throw dynamicgraph::ExceptionSignal(dynamicgraph::ExceptionSignal::GENERIC, - "Integrator does not compute the derivative."); + throw dynamicgraph::ExceptionSignal( + dynamicgraph::ExceptionSignal::GENERIC, + "Integrator does not compute the derivative."); SOUT.recompute(time); res = outputMemory[1]; diff --git a/include/sot/core/joint-limitator.hh b/include/sot/core/joint-limitator.hh index e3cce3244..efb1e9147 100644 --- a/include/sot/core/joint-limitator.hh +++ b/include/sot/core/joint-limitator.hh @@ -41,8 +41,10 @@ public: JointLimitator(const std::string &name); virtual ~JointLimitator() {} - virtual dynamicgraph::Vector &computeControl(dynamicgraph::Vector &res, int time); - dynamicgraph::Vector &computeWidthJl(dynamicgraph::Vector &res, const int &time); + virtual dynamicgraph::Vector &computeControl(dynamicgraph::Vector &res, + int time); + dynamicgraph::Vector &computeWidthJl(dynamicgraph::Vector &res, + const int &time); virtual void display(std::ostream &os) const; diff --git a/include/sot/core/joint-trajectory-entity.hh b/include/sot/core/joint-trajectory-entity.hh index 91a7aa755..d674e1322 100644 --- a/include/sot/core/joint-trajectory-entity.hh +++ b/include/sot/core/joint-trajectory-entity.hh @@ -57,7 +57,8 @@ public: void loadFile(const std::string &name); /// \brief Return the next pose for the legs. - dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, const int &time); + dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, + const int &time); /// \brief Return the next com. dynamicgraph::Vector &getNextCoM(dynamicgraph::Vector &com, const int &time); diff --git a/include/sot/core/mailbox.hh b/include/sot/core/mailbox.hh index 0aab925af..998ff45b2 100644 --- a/include/sot/core/mailbox.hh +++ b/include/sot/core/mailbox.hh @@ -31,7 +31,6 @@ namespace dynamicgraph { namespace sot { - template class Mailbox : public dynamicgraph::Entity { public: static const std::string CLASS_NAME; diff --git a/include/sot/core/motion-period.hh b/include/sot/core/motion-period.hh index 25ff16cd2..4adbf274c 100644 --- a/include/sot/core/motion-period.hh +++ b/include/sot/core/motion-period.hh @@ -46,7 +46,6 @@ namespace dynamicgraph { namespace sot { - class SOTMOTIONPERIOD_EXPORT MotionPeriod : public dynamicgraph::Entity { public: @@ -77,7 +76,8 @@ public: MotionPeriod(const std::string &name); virtual ~MotionPeriod(void) {} - dynamicgraph::Vector &computeMotion(dynamicgraph::Vector &res, const int &time); + dynamicgraph::Vector &computeMotion(dynamicgraph::Vector &res, + const int &time); virtual void display(std::ostream &os) const; }; diff --git a/include/sot/core/neck-limitation.hh b/include/sot/core/neck-limitation.hh index 23c593229..3d0a1abf9 100644 --- a/include/sot/core/neck-limitation.hh +++ b/include/sot/core/neck-limitation.hh @@ -48,7 +48,6 @@ namespace dynamicgraph { namespace sot { - class NeckLimitation_EXPORT NeckLimitation : public dynamicgraph::Entity { public: static const std::string CLASS_NAME; @@ -76,8 +75,9 @@ public: /* --- SIGNAL --- */ dynamicgraph::SignalTimeDependent jointSOUT; public: /* --- FUNCTIONS --- */ - dynamicgraph::Vector &computeJointLimitation(dynamicgraph::Vector &jointLimited, - const int &timeSpec); + dynamicgraph::Vector & + computeJointLimitation(dynamicgraph::Vector &jointLimited, + const int &timeSpec); public: /* --- PARAMS --- */ virtual void display(std::ostream &os) const; diff --git a/include/sot/core/op-point-modifier.hh b/include/sot/core/op-point-modifier.hh index 809c0dfd3..d0de4871d 100644 --- a/include/sot/core/op-point-modifier.hh +++ b/include/sot/core/op-point-modifier.hh @@ -61,7 +61,8 @@ public: OpPointModifier(const std::string &name); virtual ~OpPointModifier(void) {} - dynamicgraph::Matrix &jacobianSOUT_function(dynamicgraph::Matrix &res, const int &time); + dynamicgraph::Matrix &jacobianSOUT_function(dynamicgraph::Matrix &res, + const int &time); MatrixHomogeneous &positionSOUT_function(MatrixHomogeneous &res, const int &time); void setTransformation(const Eigen::Matrix4d &tr); diff --git a/include/sot/core/parameter-server.hh b/include/sot/core/parameter-server.hh index c6e858a52..1275f0eaf 100644 --- a/include/sot/core/parameter-server.hh +++ b/include/sot/core/parameter-server.hh @@ -60,7 +60,7 @@ public: /* --- CONSTRUCTOR ---- */ ParameterServer(const std::string &name); - ~ParameterServer() {}; + ~ParameterServer(){}; /// Initialize /// @param dt: control interval diff --git a/include/sot/core/reader.hh b/include/sot/core/reader.hh index 7c216aea5..fee84b225 100644 --- a/include/sot/core/reader.hh +++ b/include/sot/core/reader.hh @@ -17,7 +17,6 @@ /* Matrix */ #include - /* STD */ #include #include @@ -80,8 +79,10 @@ protected: int rows, cols; - dynamicgraph::Vector &getNextData(dynamicgraph::Vector &res, const unsigned int time); - dynamicgraph::Matrix &getNextMatrix(dynamicgraph::Matrix &res, const unsigned int time); + dynamicgraph::Vector &getNextData(dynamicgraph::Vector &res, + const unsigned int time); + dynamicgraph::Matrix &getNextMatrix(dynamicgraph::Matrix &res, + const unsigned int time); void resize(const int &nbRow, const int &nbCol); public: diff --git a/include/sot/core/robot-utils.hh b/include/sot/core/robot-utils.hh index 6ddaafba9..7f0e1737d 100644 --- a/include/sot/core/robot-utils.hh +++ b/include/sot/core/robot-utils.hh @@ -18,7 +18,6 @@ #include #include - namespace dynamicgraph { namespace sot { @@ -55,7 +54,8 @@ struct SOT_CORE_EXPORT ForceUtil { void set_name_to_force_id(const std::string &name, const Index &force_id); - void set_force_id_to_limits(const Index &force_id, const dynamicgraph::Vector &lf, + void set_force_id_to_limits(const Index &force_id, + const dynamicgraph::Vector &lf, const dynamicgraph::Vector &uf); void create_force_id_to_name_map(); @@ -244,7 +244,7 @@ RobotUtilShrPtr RefVoidRobotUtil(); RobotUtilShrPtr getRobotUtil(std::string &robotName); bool isNameInRobotUtil(std::string &robotName); RobotUtilShrPtr createRobotUtil(std::string &robotName); -std::shared_ptr< std::vector > getListOfRobots(); +std::shared_ptr > getListOfRobots(); bool base_se3_to_sot(ConstRefVector pos, ConstRefMatrix R, RefVector q_sot); diff --git a/include/sot/core/seq-play.hh b/include/sot/core/seq-play.hh index 6be8ca4e3..fb7dd5ef9 100644 --- a/include/sot/core/seq-play.hh +++ b/include/sot/core/seq-play.hh @@ -64,7 +64,8 @@ public: void loadFile(const std::string &name); - dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, const int &time); + dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, + const int &time); public: /* --- DISPLAY --- */ virtual void display(std::ostream &os) const; diff --git a/include/sot/core/seqplay.hh b/include/sot/core/seqplay.hh index 6be8ca4e3..fb7dd5ef9 100644 --- a/include/sot/core/seqplay.hh +++ b/include/sot/core/seqplay.hh @@ -64,7 +64,8 @@ public: void loadFile(const std::string &name); - dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, const int &time); + dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, + const int &time); public: /* --- DISPLAY --- */ virtual void display(std::ostream &os) const; diff --git a/include/sot/core/smooth-reach.hh b/include/sot/core/smooth-reach.hh index 5848bb190..3f64dbc5e 100644 --- a/include/sot/core/smooth-reach.hh +++ b/include/sot/core/smooth-reach.hh @@ -38,7 +38,6 @@ namespace dynamicgraph { namespace sot { - /* --------------------------------------------------------------------- */ /* --- CLASS ----------------------------------------------------------- */ /* --------------------------------------------------------------------- */ @@ -66,7 +65,8 @@ public: /* --- SIGNAL --- */ dynamicgraph::SignalTimeDependent goalSOUT; public: /* --- FUNCTION --- */ - dynamicgraph::Vector &goalSOUT_function(dynamicgraph::Vector &goal, const int &time); + dynamicgraph::Vector &goalSOUT_function(dynamicgraph::Vector &goal, + const int &time); void set(const dynamicgraph::Vector &goal, const int &length); const dynamicgraph::Vector &getGoal(void); diff --git a/include/sot/core/sot.hh b/include/sot/core/sot.hh index 067573571..30d3ba0c2 100644 --- a/include/sot/core/sot.hh +++ b/include/sot/core/sot.hh @@ -158,7 +158,8 @@ public: /* --- CONTROL --- */ */ /*! \brief Compute the control law. */ - virtual dynamicgraph::Vector &computeControlLaw(dynamicgraph::Vector &control, const int &time); + virtual dynamicgraph::Vector &computeControlLaw(dynamicgraph::Vector &control, + const int &time); /*! @} */ diff --git a/include/sot/core/task.hh b/include/sot/core/task.hh index 7417a0342..53bbfb9b5 100644 --- a/include/sot/core/task.hh +++ b/include/sot/core/task.hh @@ -101,7 +101,8 @@ public: VectorMultiBound &computeTaskExponentialDecrease(VectorMultiBound &errorRef, int time); dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &J, int time); - dynamicgraph::Vector &computeErrorTimeDerivative(dynamicgraph::Vector &res, int time); + dynamicgraph::Vector &computeErrorTimeDerivative(dynamicgraph::Vector &res, + int time); /* --- SIGNALS ------------------------------------------------------------ */ public: @@ -109,7 +110,8 @@ public: dynamicgraph::SignalPtr dampingGainSINOUT; dynamicgraph::SignalPtr controlSelectionSIN; dynamicgraph::SignalTimeDependent errorSOUT; - dynamicgraph::SignalTimeDependent errorTimeDerivativeSOUT; + dynamicgraph::SignalTimeDependent + errorTimeDerivativeSOUT; /* --- DISPLAY ------------------------------------------------------------ */ void display(std::ostream &os) const; diff --git a/include/sot/core/time-stamp.hh b/include/sot/core/time-stamp.hh index 93b3d9918..ceb6c6967 100644 --- a/include/sot/core/time-stamp.hh +++ b/include/sot/core/time-stamp.hh @@ -79,7 +79,8 @@ public: /* --- SIGNALS --- */ dynamicgraph::SignalTimeDependent timeOnceDoubleSOUT; protected: /* --- SIGNAL FUNCTIONS --- */ - dynamicgraph::Vector &getTimeStamp(dynamicgraph::Vector &res, const int &time); + dynamicgraph::Vector &getTimeStamp(dynamicgraph::Vector &res, + const int &time); double &getTimeStampDouble(const dynamicgraph::Vector &vect, double &res); }; diff --git a/include/sot/core/trajectory.hh b/include/sot/core/trajectory.hh index b6957f8e1..6f05c6e2f 100644 --- a/include/sot/core/trajectory.hh +++ b/include/sot/core/trajectory.hh @@ -17,7 +17,6 @@ #include #include - namespace dynamicgraph { namespace sot { @@ -121,8 +120,8 @@ public: typedef std::vector vec_ref; void display(std::ostream &os) const { - boost::array names = - boost::assign::list_of("Positions")("Velocities")("Accelerations")("Effort"); + boost::array names = boost::assign::list_of("Positions")( + "Velocities")("Accelerations")("Effort"); const std::vector *points = 0; diff --git a/include/sot/core/vector-to-rotation.hh b/include/sot/core/vector-to-rotation.hh index 9a4bb2aeb..bfe22e70c 100644 --- a/include/sot/core/vector-to-rotation.hh +++ b/include/sot/core/vector-to-rotation.hh @@ -40,7 +40,8 @@ namespace dynamicgraph { namespace sot { -class SOTVECTORTOROTATION_EXPORT VectorToRotation : public dynamicgraph::Entity { +class SOTVECTORTOROTATION_EXPORT VectorToRotation + : public dynamicgraph::Entity { static const std::string CLASS_NAME; virtual const std::string &getClassName(void) const { return CLASS_NAME; } diff --git a/src/feature/feature-pose.cpp b/src/feature/feature-pose.cpp index f328281c4..d76605e53 100644 --- a/src/feature/feature-pose.cpp +++ b/src/feature/feature-pose.cpp @@ -41,5 +41,5 @@ namespace dynamicgraph { namespace sot { template class FeaturePose; template class FeaturePose; -} -} +} // namespace sot +} // namespace dynamicgraph diff --git a/src/sot/sot.cpp b/src/sot/sot.cpp index 817b50f08..01a5c8a4a 100644 --- a/src/sot/sot.cpp +++ b/src/sot/sot.cpp @@ -505,8 +505,9 @@ dynamicgraph::Vector &Sot::computeControlLaw(dynamicgraph::Vector &control, makeMap(kernel, K); has_kernel = true; } else { - DYNAMIC_GRAPH_ENTITY_ERROR_STREAM(*this) << "Projector of " << getName() - << " has " << K.rows() << " rows while " << nbJoints << " expected.\n"; + DYNAMIC_GRAPH_ENTITY_ERROR_STREAM(*this) + << "Projector of " << getName() << " has " << K.rows() + << " rows while " << nbJoints << " expected.\n"; } } for (StackType::iterator iter = stack.begin(); iter != stack.end(); ++iter) { diff --git a/src/tools/parameter-server.cpp b/src/tools/parameter-server.cpp index 437013089..1ac3b0807 100644 --- a/src/tools/parameter-server.cpp +++ b/src/tools/parameter-server.cpp @@ -61,11 +61,11 @@ ParameterServer::ParameterServer(const std::string &name) "Time period in seconds (double)", "URDF file path (string)", "Robot reference (string)"))); - addCommand("init_simple", - makeCommandVoid1(*this, &ParameterServer::init_simple, - docCommandVoid1("Initialize the entity.", - "Time period in seconds (double)" - ))); + addCommand( + "init_simple", + makeCommandVoid1(*this, &ParameterServer::init_simple, + docCommandVoid1("Initialize the entity.", + "Time period in seconds (double)"))); addCommand("setNameToId", makeCommandVoid2(*this, &ParameterServer::setNameToId, @@ -144,7 +144,7 @@ ParameterServer::ParameterServer(const std::string &name) "(string) ParameterName"))); } -void ParameterServer::init_simple(const double & dt) { +void ParameterServer::init_simple(const double &dt) { if (dt <= 0.0) return SEND_MSG("Timestep must be positive", MSG_TYPE_ERROR); @@ -155,10 +155,10 @@ void ParameterServer::init_simple(const double & dt) { m_initSucceeded = true; std::string localName("robot"); - std::shared_ptr< std::vector > - listOfRobots = sot::getListOfRobots(); + std::shared_ptr > listOfRobots = + sot::getListOfRobots(); - if (listOfRobots->size()==1) + if (listOfRobots->size() == 1) localName = (*listOfRobots)[0]; else { throw ExceptionTools(ExceptionTools::ErrorCodeEnum::PARAMETER_SERVER, @@ -176,7 +176,6 @@ void ParameterServer::init_simple(const double & dt) { makeDirectGetter(*this, &m_robot_util->m_dgv_urdf_to_sot, docDirectSetter("Display map Joints From URDF to SoT.", "Vector of integer for mapping"))); - } void ParameterServer::init(const double &dt, const std::string &urdfFile, @@ -195,7 +194,6 @@ void ParameterServer::init(const double &dt, const std::string &urdfFile, } m_robot_util->m_urdf_filename = urdfFile; - } /* ------------------------------------------------------------------- */ diff --git a/src/tools/robot-utils.cpp b/src/tools/robot-utils.cpp index fbc545825..565b8d8c3 100644 --- a/src/tools/robot-utils.cpp +++ b/src/tools/robot-utils.cpp @@ -438,18 +438,17 @@ bool base_sot_to_urdf(ConstRefVector q_sot, RefVector q_urdf) { std::map sgl_map_name_to_robot_util; -std::shared_ptr > getListOfRobots() { +std::shared_ptr > getListOfRobots() { std::shared_ptr > res = std::make_shared >(); - + std::map::iterator it = sgl_map_name_to_robot_util.begin(); - while (it != sgl_map_name_to_robot_util.end()) - { + while (it != sgl_map_name_to_robot_util.end()) { res->push_back(it->first); it++; } - + return res; } diff --git a/tests/features/test_feature_generic.cpp b/tests/features/test_feature_generic.cpp index 18ad6645b..87651211b 100644 --- a/tests/features/test_feature_generic.cpp +++ b/tests/features/test_feature_generic.cpp @@ -26,8 +26,8 @@ #include #include -#include #include +#include #include #include #include @@ -51,9 +51,9 @@ template struct LG_t { typedef typename boost::mpl::if_c::type type; }; -} -} -} +} // namespace internal +} // namespace sot +} // namespace dynamicgraph using namespace std; using namespace dynamicgraph::sot; @@ -345,7 +345,6 @@ class TestFeaturePose : public FeatureTestBase { setJointFrame(); } - void _setFrame() { setSignal( feature_.jaMfa,