Skip to content

Commit

Permalink
Format
Browse files Browse the repository at this point in the history
  • Loading branch information
nim65s committed Jul 23, 2020
1 parent 90876e4 commit 461d122
Show file tree
Hide file tree
Showing 46 changed files with 163 additions and 125 deletions.
6 changes: 4 additions & 2 deletions include/sot/core/clamp-workspace.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
3 changes: 2 additions & 1 deletion include/sot/core/com-freezer.hh
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ public: /* --- SIGNAL --- */
dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> 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;
Expand Down
1 change: 0 additions & 1 deletion include/sot/core/control-gr.hh
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@
namespace dynamicgraph {
namespace sot {


/* --------------------------------------------------------------------- */
/* --- CLASS ----------------------------------------------------------- */
/* --------------------------------------------------------------------- */
Expand Down
6 changes: 4 additions & 2 deletions include/sot/core/control-pd.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions include/sot/core/device.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
1 change: 0 additions & 1 deletion include/sot/core/exp-moving-avg.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include <dynamic-graph/signal-time-dependent.h>
#include <sot/core/config.hh>


namespace dynamicgraph {
namespace sot {

Expand Down
6 changes: 4 additions & 2 deletions include/sot/core/feature-1d.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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);

/*! @} */

Expand Down
9 changes: 6 additions & 3 deletions include/sot/core/feature-abstract.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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);

/*! @} */

Expand Down
6 changes: 4 additions & 2 deletions include/sot/core/feature-generic.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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);

/*! @} */

Expand Down
9 changes: 6 additions & 3 deletions include/sot/core/feature-joint-limits.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
9 changes: 6 additions & 3 deletions include/sot/core/feature-line-distance.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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;
};
Expand Down
12 changes: 8 additions & 4 deletions include/sot/core/feature-point6d-relative.hh
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,8 @@ protected:
/* --- SIGNALS ------------------------------------------------------------ */
public:
dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionReferenceSIN;
dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianReferenceSIN;
dynamicgraph::SignalPtr<dynamicgraph::Matrix, int>
articularJacobianReferenceSIN;

/*! dynamicgraph::Signals related to the computation of the derivative of
the error
Expand All @@ -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;

Expand Down
9 changes: 6 additions & 3 deletions include/sot/core/feature-point6d.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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; }
Expand Down
15 changes: 9 additions & 6 deletions include/sot/core/feature-pose.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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<Scalar,Options>::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; }
Expand All @@ -160,10 +163,10 @@ private:
/// \todo Intermediate variables for internal computations
};

template < typename T >
template <typename T>
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<SE3Representation>;
extern template class SOT_CORE_DLLAPI FeaturePose<R3xSO3Representation>;
Expand Down
17 changes: 6 additions & 11 deletions include/sot/core/feature-pose.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ template <Representation_t representation> struct LG_t {
typedef typename boost::mpl::if_c<representation == SE3Representation, SE3_t,
R3xSO3_t>::type type;
};
}
} // namespace internal

/* --------------------------------------------------------------------- */
/* --- CLASS ----------------------------------------------------------- */
Expand Down Expand Up @@ -104,11 +104,7 @@ FeaturePose<representation>::FeaturePose(const std::string &pointName)
}

template <Representation_t representation>
FeaturePose<representation>::~FeaturePose()
{
}


FeaturePose<representation>::~FeaturePose() {}

/* --------------------------------------------------------------------- */
/* --------------------------------------------------------------------- */
Expand Down Expand Up @@ -261,8 +257,8 @@ Vector &FeaturePose<representation>::computeError(Vector &error, int time) {
// feature (R^3xSO(3) or SE(3)), in the right frame.
template <>
Vector6d convertVelocity<SE3_t>(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);
Expand Down Expand Up @@ -351,6 +347,5 @@ void FeaturePose<representation>::display(std::ostream &os) const {
}
}


}
}
} // namespace sot
} // namespace dynamicgraph
6 changes: 4 additions & 2 deletions include/sot/core/feature-posture.hh
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,8 @@ class SOTFEATUREPOSTURE_EXPORT FeaturePosture : public FeatureAbstract {

public:
typedef dynamicgraph::SignalPtr<dynamicgraph::Vector, int> signalIn_t;
typedef dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> signalOut_t;
typedef dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int>
signalOut_t;

DECLARE_NO_REFERENCE;

Expand All @@ -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_;
Expand Down
1 change: 0 additions & 1 deletion include/sot/core/feature-task.hh
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@
namespace dynamicgraph {
namespace sot {


class SOTFEATURETASK_EXPORT FeatureTask : public FeatureGeneric {

public:
Expand Down
6 changes: 4 additions & 2 deletions include/sot/core/feature-vector3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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;
};
Expand Down
6 changes: 4 additions & 2 deletions include/sot/core/feature-visual-point.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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; }
Expand Down
1 change: 0 additions & 1 deletion include/sot/core/fir-filter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#include <dynamic-graph/command-setter.h>
#include <dynamic-graph/entity.h>


namespace dynamicgraph {
namespace sot {

Expand Down
1 change: 0 additions & 1 deletion include/sot/core/gradient-ascent.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include <dynamic-graph/signal-time-dependent.h>
#include <sot/core/config.hh>


namespace dynamicgraph {
namespace sot {

Expand Down
Loading

0 comments on commit 461d122

Please sign in to comment.