Skip to content

Use long int for signal time and simplify SignalPtr #220

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 14 commits into from
Jul 28, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 0 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -100,9 +100,6 @@ set(${PROJECT_NAME}_HEADERS
include/${CUSTOM_HEADER_DIR}/latch.hh
include/${CUSTOM_HEADER_DIR}/macros.hh
include/${CUSTOM_HEADER_DIR}/macros-signal.hh
include/${CUSTOM_HEADER_DIR}/mailbox-vector.hh
include/${CUSTOM_HEADER_DIR}/mailbox.hh
include/${CUSTOM_HEADER_DIR}/mailbox.hxx
include/${CUSTOM_HEADER_DIR}/matrix-constant.hh
include/${CUSTOM_HEADER_DIR}/matrix-geometry.hh
include/${CUSTOM_HEADER_DIR}/matrix-svd.hh
Expand Down Expand Up @@ -135,7 +132,6 @@ set(${PROJECT_NAME}_HEADERS
include/${CUSTOM_HEADER_DIR}/utils-windows.hh
include/${CUSTOM_HEADER_DIR}/variadic-op.hh
include/${CUSTOM_HEADER_DIR}/vector-constant.hh
include/${CUSTOM_HEADER_DIR}/vector-to-rotation.hh
include/${CUSTOM_HEADER_DIR}/visual-point-projecter.hh)

set(${PROJECT_NAME}_SOURCES
Expand Down
3 changes: 2 additions & 1 deletion include/sot/core/abstract-sot-external-interface.hh
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@

#include <map>
#include <sot/core/api.hh>
#include <sot/core/fwd.hh>
#include <string>
#include <vector>

Expand Down Expand Up @@ -61,7 +62,7 @@ class SOT_CORE_EXPORT AbstractSotExternalInterface {
virtual void setSecondOrderIntegration(void) = 0;
virtual void setNoIntegration(void) = 0;
// Set the number of joints that are controlled
virtual void setControlSize(const int &) = 0;
virtual void setControlSize(const size_type &) = 0;
};
} // namespace sot
} // namespace dynamicgraph
Expand Down
2 changes: 1 addition & 1 deletion include/sot/core/admittance-control-op-point.hh
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ class ADMITTANCECONTROLOPPOINT_EXPORT AdmittanceControlOpPoint

protected:
/// Dimension of the force signals and of the output
int m_n;
size_type m_n;
/// True if the entity has been successfully initialized
bool m_initSucceeded;
/// Internal state
Expand Down
6 changes: 3 additions & 3 deletions include/sot/core/binary-int-to-uint.hh
Original file line number Diff line number Diff line change
Expand Up @@ -44,14 +44,14 @@ class SOTBINARYINTTOUINT_EXPORT BinaryIntToUint : public dynamicgraph::Entity {

/* --- SIGNALS ------------------------------------------------------------ */
public:
dynamicgraph::SignalPtr<int, int> binaryIntSIN;
dynamicgraph::SignalTimeDependent<unsigned, int> binaryUintSOUT;
dynamicgraph::SignalPtr<int, sigtime_t> binaryIntSIN;
dynamicgraph::SignalTimeDependent<unsigned, sigtime_t> binaryUintSOUT;

public:
BinaryIntToUint(const std::string &name);
virtual ~BinaryIntToUint() {}

virtual unsigned &computeOutput(unsigned &res, int time);
virtual unsigned int &computeOutput(unsigned int &res, sigtime_t time);

virtual void display(std::ostream &os) const;
};
Expand Down
8 changes: 4 additions & 4 deletions include/sot/core/binary-op.hh
Original file line number Diff line number Diff line change
Expand Up @@ -68,12 +68,12 @@ class BinaryOp : public Entity {
virtual ~BinaryOp(void){};

public: /* --- SIGNAL --- */
SignalPtr<Tin1, int> SIN1;
SignalPtr<Tin2, int> SIN2;
SignalTimeDependent<Tout, int> SOUT;
SignalPtr<Tin1, sigtime_t> SIN1;
SignalPtr<Tin2, sigtime_t> SIN2;
SignalTimeDependent<Tout, sigtime_t> SOUT;

protected:
Tout &computeOperation(Tout &res, int time) {
Tout &computeOperation(Tout &res, sigtime_t time) {
const Tin1 &x1 = SIN1(time);
const Tin2 &x2 = SIN2(time);
op(x1, x2, res);
Expand Down
10 changes: 5 additions & 5 deletions include/sot/core/causal-filter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
/* --------------------------------------------------------------------- */
/* --- INCLUDE --------------------------------------------------------- */
/* --------------------------------------------------------------------- */
#include <Eigen/Core>
#include <sot/core/fwd.hh>

/** \addtogroup Filters
\section subsec_causalfilter CausalFilter
Expand Down Expand Up @@ -54,7 +54,7 @@ class CausalFilter {

xSize is
*/
CausalFilter(const double &timestep, const int &xSize,
CausalFilter(const double &timestep, const size_type &xSize,
const Eigen::VectorXd &filter_numerator,
const Eigen::VectorXd &filter_denominator);

Expand All @@ -68,7 +68,7 @@ class CausalFilter {
/// sampling timestep of the input signal
double m_dt;
/// Size
int m_x_size;
size_type m_x_size;
/// Size of the numerator \f$m\f$
Eigen::VectorXd::Index m_filter_order_m;
/// Size of the denominator \f$n\f$
Expand All @@ -80,8 +80,8 @@ class CausalFilter {
Eigen::VectorXd m_filter_denominator;
bool m_first_sample;
///
int m_pt_numerator;
int m_pt_denominator;
size_type m_pt_numerator;
size_type m_pt_denominator;
Eigen::MatrixXd m_input_buffer;
Eigen::MatrixXd m_output_buffer;
}; // class CausalFilter
Expand Down
23 changes: 12 additions & 11 deletions include/sot/core/clamp-workspace.hh
Original file line number Diff line number Diff line change
Expand Up @@ -51,28 +51,29 @@ class SOTCLAMPWORKSPACE_EXPORT ClampWorkspace : public dynamicgraph::Entity {

/* --- SIGNALS ------------------------------------------------------------ */
public:
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;
dynamicgraph::SignalPtr<MatrixHomogeneous, sigtime_t> positionrefSIN;
dynamicgraph::SignalPtr<MatrixHomogeneous, sigtime_t> positionSIN;
dynamicgraph::SignalTimeDependent<dynamicgraph::Matrix, sigtime_t> alphaSOUT;
dynamicgraph::SignalTimeDependent<dynamicgraph::Matrix, sigtime_t>
alphabarSOUT;
dynamicgraph::SignalTimeDependent<MatrixHomogeneous, sigtime_t> handrefSOUT;

public:
ClampWorkspace(const std::string &name);
virtual ~ClampWorkspace(void) {}

void update(int time);
void update(sigtime_t time);

virtual dynamicgraph::Matrix &computeOutput(dynamicgraph::Matrix &res,
int time);
sigtime_t time);
virtual dynamicgraph::Matrix &computeOutputBar(dynamicgraph::Matrix &res,
int time);
virtual MatrixHomogeneous &computeRef(MatrixHomogeneous &res, int time);
sigtime_t time);
virtual MatrixHomogeneous &computeRef(MatrixHomogeneous &res, sigtime_t time);

virtual void display(std::ostream &) const;

private:
int timeUpdate;
sigtime_t timeUpdate;

dynamicgraph::Matrix alpha;
dynamicgraph::Matrix alphabar;
Expand All @@ -89,7 +90,7 @@ class SOTCLAMPWORKSPACE_EXPORT ClampWorkspace : public dynamicgraph::Entity {
double dm_max_yaw;
double theta_min;
double theta_max;
int mode;
size_type mode;

enum { FRAME_POINT, FRAME_REF } frame;

Expand Down
11 changes: 6 additions & 5 deletions include/sot/core/com-freezer.hh
Original file line number Diff line number Diff line change
Expand Up @@ -50,20 +50,21 @@ class SOTCOMFREEZER_EXPORT CoMFreezer : public dynamicgraph::Entity {
private:
dynamicgraph::Vector m_lastCoM;
bool m_previousPGInProcess;
int m_lastStopTime;
sigtime_t m_lastStopTime;

public: /* --- CONSTRUCTION --- */
CoMFreezer(const std::string &name);
virtual ~CoMFreezer(void);

public: /* --- SIGNAL --- */
dynamicgraph::SignalPtr<dynamicgraph::Vector, int> CoMRefSIN;
dynamicgraph::SignalPtr<unsigned, int> PGInProcessSIN;
dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> freezedCoMSOUT;
dynamicgraph::SignalPtr<dynamicgraph::Vector, sigtime_t> CoMRefSIN;
dynamicgraph::SignalPtr<unsigned, sigtime_t> PGInProcessSIN;
dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, sigtime_t>
freezedCoMSOUT;

public: /* --- FUNCTION --- */
dynamicgraph::Vector &computeFreezedCoM(dynamicgraph::Vector &freezedCoM,
const int &time);
const sigtime_t &time);

public: /* --- PARAMS --- */
virtual void display(std::ostream &os) const;
Expand Down
2 changes: 1 addition & 1 deletion include/sot/core/contiifstream.hh
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ class SOT_CORE_EXPORT Contiifstream {
protected:
std::string filename;
std::streamoff cursor;
static const unsigned int BUFFER_SIZE = 256;
static const std::size_t BUFFER_SIZE = 256;
char buffer[BUFFER_SIZE];
std::list<std::string> reader;
bool first;
Expand Down
12 changes: 6 additions & 6 deletions include/sot/core/control-gr.hh
Original file line number Diff line number Diff line change
Expand Up @@ -66,14 +66,14 @@ class ControlGR_EXPORT ControlGR : public Entity {
double _dimension;

public: /* --- SIGNALS --- */
SignalPtr<dynamicgraph::Matrix, int> matrixASIN;
SignalPtr<dynamicgraph::Vector, int> accelerationSIN;
SignalPtr<dynamicgraph::Vector, int> gravitySIN;
SignalTimeDependent<dynamicgraph::Vector, int> controlSOUT;
SignalPtr<dynamicgraph::Matrix, sigtime_t> matrixASIN;
SignalPtr<dynamicgraph::Vector, sigtime_t> accelerationSIN;
SignalPtr<dynamicgraph::Vector, sigtime_t> gravitySIN;
SignalTimeDependent<dynamicgraph::Vector, sigtime_t> controlSOUT;

protected:
double &setsize(int dimension);
dynamicgraph::Vector &computeControl(dynamicgraph::Vector &tau, int t);
double &setsize(size_type dimension);
dynamicgraph::Vector &computeControl(dynamicgraph::Vector &tau, sigtime_t t);
};

} // namespace sot
Expand Down
24 changes: 12 additions & 12 deletions include/sot/core/control-pd.hh
Original file line number Diff line number Diff line change
Expand Up @@ -65,24 +65,24 @@ class ControlPD_EXPORT ControlPD : public Entity {
double TimeStep;

public: /* --- SIGNALS --- */
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;
SignalPtr<dynamicgraph::Vector, sigtime_t> KpSIN;
SignalPtr<dynamicgraph::Vector, sigtime_t> KdSIN;
SignalPtr<dynamicgraph::Vector, sigtime_t> positionSIN;
SignalPtr<dynamicgraph::Vector, sigtime_t> desiredpositionSIN;
SignalPtr<dynamicgraph::Vector, sigtime_t> velocitySIN;
SignalPtr<dynamicgraph::Vector, sigtime_t> desiredvelocitySIN;
SignalTimeDependent<dynamicgraph::Vector, sigtime_t> controlSOUT;
SignalTimeDependent<dynamicgraph::Vector, sigtime_t> positionErrorSOUT;
SignalTimeDependent<dynamicgraph::Vector, sigtime_t> velocityErrorSOUT;

protected:
dynamicgraph::Vector &computeControl(dynamicgraph::Vector &tau, int t);
dynamicgraph::Vector &computeControl(dynamicgraph::Vector &tau, sigtime_t t);
dynamicgraph::Vector position_error_;
dynamicgraph::Vector velocity_error_;
dynamicgraph::Vector &getPositionError(dynamicgraph::Vector &position_error,
int t);
sigtime_t t);
dynamicgraph::Vector &getVelocityError(dynamicgraph::Vector &velocity_error,
int t);
sigtime_t t);
};

} // namespace sot
Expand Down
27 changes: 15 additions & 12 deletions include/sot/core/debug.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <sstream>

#include "sot/core/api.hh"
#include "sot/core/fwd.hh"

#ifndef VP_DEBUG_MODE
#define VP_DEBUG_MODE 0
Expand All @@ -37,17 +38,17 @@ namespace dynamicgraph {
namespace sot {
class SOT_CORE_EXPORT DebugTrace {
public:
static const int SIZE = 512;
static const size_type SIZE = 512;

std::stringstream tmpbuffer;
std::ostream &outputbuffer;
char charbuffer[SIZE + 1];
int traceLevel;
int traceLevelTemplate;
size_type traceLevel;
size_type traceLevelTemplate;

DebugTrace(std::ostream &os) : outputbuffer(os) {}

inline void trace(const int level, const char *format, ...) {
inline void trace(const size_type level, const char *format, ...) {
if (level <= traceLevel) SOT_COMMON_TRACES;
tmpbuffer.str("");
}
Expand All @@ -57,12 +58,12 @@ class SOT_CORE_EXPORT DebugTrace {
tmpbuffer.str("");
}

inline void trace(const int level = -1) {
inline void trace(const size_type level = -1) {
if (level <= traceLevel) outputbuffer << tmpbuffer.str();
tmpbuffer.str("");
}

inline void traceTemplate(const int level, const char *format, ...) {
inline void traceTemplate(const size_type level, const char *format, ...) {
if (level <= traceLevelTemplate) SOT_COMMON_TRACES;
tmpbuffer.str("");
}
Expand All @@ -74,7 +75,7 @@ class SOT_CORE_EXPORT DebugTrace {

inline DebugTrace &pre(const std::ostream &) { return *this; }

inline DebugTrace &pre(const std::ostream &, int level) {
inline DebugTrace &pre(const std::ostream &, size_type level) {
traceLevel = level;
return *this;
}
Expand Down Expand Up @@ -150,9 +151,11 @@ SOT_CORE_EXPORT extern DebugTrace sotERRORFLOW;

namespace dynamicgraph {
namespace sot {
inline bool sotDEBUG_ENABLE(const int &level) { return level <= VP_DEBUG_MODE; }
inline bool sotDEBUG_ENABLE(const size_type &level) {
return level <= VP_DEBUG_MODE;
}

inline bool sotTDEBUG_ENABLE(const int &level) {
inline bool sotTDEBUG_ENABLE(const size_type &level) {
return level <= VP_TEMPLATE_DEBUG_MODE;
}
} // namespace sot
Expand All @@ -176,9 +179,9 @@ inline bool sotTDEBUG_ENABLE(const int &level) {

namespace dynamicgraph {
namespace sot {
inline void sotDEBUGF(const int, const char *, ...) {}
inline void sotDEBUGF(const size_type, const char *, ...) {}
inline void sotDEBUGF(const char *, ...) {}
inline void sotERRORF(const int, const char *, ...) {}
inline void sotERRORF(const size_type, const char *, ...) {}
inline void sotERRORF(const char *, ...) {}
inline std::ostream &__null_stream() {
// This function should never be called. With -O3,
Expand All @@ -198,7 +201,7 @@ inline std::ostream &__null_stream() {

namespace dynamicgraph {
namespace sot {
inline void sotTDEBUGF(const int, const char *, ...) {}
inline void sotTDEBUGF(const size_type, const char *, ...) {}
inline void sotTDEBUGF(const char *, ...) {}
} // namespace sot
} // namespace dynamicgraph
Expand Down
10 changes: 5 additions & 5 deletions include/sot/core/derivator.hh
Original file line number Diff line number Diff line change
Expand Up @@ -68,12 +68,12 @@ class Derivator : public dynamicgraph::Entity {
virtual ~Derivator(void){};

public: /* --- SIGNAL --- */
dynamicgraph::SignalPtr<T, int> SIN;
dynamicgraph::SignalTimeDependent<T, int> SOUT;
dynamicgraph::Signal<double, int> timestepSIN;
dynamicgraph::SignalPtr<T, sigtime_t> SIN;
dynamicgraph::SignalTimeDependent<T, sigtime_t> SOUT;
dynamicgraph::Signal<double, sigtime_t> timestepSIN;

protected:
T &computeDerivation(T &res, int time) {
T &computeDerivation(T &res, sigtime_t time) {
if (initialized) {
res = memory;
res *= -1;
Expand All @@ -92,7 +92,7 @@ class Derivator : public dynamicgraph::Entity {
// TODO Derivation of unit quaternion?
template <>
VectorQuaternion &Derivator<VectorQuaternion>::computeDerivation(
VectorQuaternion &res, int time) {
VectorQuaternion &res, sigtime_t time) {
if (initialized) {
res = memory;
res.coeffs() *= -1;
Expand Down
Loading