Skip to content

Fixing warning types involved by size_type and long ambiguity. #222

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

Open
wants to merge 2 commits into
base: devel
Choose a base branch
from
Open
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
2 changes: 1 addition & 1 deletion cmake
Submodule cmake updated 101 files
2 changes: 1 addition & 1 deletion include/sot/core/device.hh
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ class SOT_CORE_EXPORT Device : public Entity {
/* --- DESTRUCTION --- */
virtual ~Device();

virtual void setStateSize(const size_type &size);
virtual void setStateSize(const std::int64_t &size);
// Set number of joints that are controlled by the device.
void setControlSize(const size_type &size);
// Get the number of joints that are controlled by the device.
Expand Down
2 changes: 1 addition & 1 deletion include/sot/core/feature-posture.hh
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class SOTFEATUREPOSTURE_EXPORT FeaturePosture : public FeatureAbstract {

private:
std::vector<bool> activeDofs_;
std::size_t nbActiveDofs_;
dynamicgraph::size_type nbActiveDofs_;
}; // class FeaturePosture
} // namespace sot
} // namespace dynamicgraph
Expand Down
6 changes: 4 additions & 2 deletions include/sot/core/filter-differentiator.hh
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@
#include <sot/core/causal-filter.hh>
#include <sot/core/stop-watch.hh>

#include <cstdint>

namespace dynamicgraph {
namespace sot {
/** \addtogroup Filters
Expand Down Expand Up @@ -84,7 +86,7 @@ class SOTFILTERDIFFERENTIATOR_EXPORT FilterDifferentiator

protected:
double m_dt; /// sampling timestep of the input signal
size_type m_x_size;
std::int64_t m_x_size;

/// polynomial-fitting filters
CausalFilter *m_filter;
Expand All @@ -106,7 +108,7 @@ class SOTFILTERDIFFERENTIATOR_EXPORT FilterDifferentiator
* polynomial fitting. The larger the delay,
* the smoother the estimations.
*/
void init(const double &timestep, const size_type &xSize,
void init(const double &timestep, const std::int64_t &xSize,
const Eigen::VectorXd &filter_numerator,
const Eigen::VectorXd &filter_denominator);

Expand Down
17 changes: 9 additions & 8 deletions include/sot/core/fir-filter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <algorithm>
#include <cassert>
#include <cstdint>
#include <iterator>
#include <vector>

Expand Down Expand Up @@ -147,15 +148,15 @@ class FIRFilter : public Entity {
"\n"
" Input:\n"
" - positive int: size\n";
addCommand("setSize", new Setter<FIRFilter, std::size_t>(
addCommand("setSize", new Setter<FIRFilter, std::int64_t>(
*this, &FIRFilter::resizeBuffer, docstring));

docstring =
" Get Number of coefficients\n"
"\n"
" Return:\n"
" - positive int: size\n";
addCommand("getSize", new Getter<FIRFilter, std::size_t>(
addCommand("getSize", new Getter<FIRFilter, std::int64_t>(
*this, &FIRFilter::getBufferSize, docstring));
}

Expand All @@ -174,14 +175,14 @@ class FIRFilter : public Entity {
return res;
}

void resizeBuffer(const std::size_t &size) {
size_t s = static_cast<size_t>(size);
void resizeBuffer(const std::int64_t &size) {
std::int64_t s = static_cast<size_t>(size);
data.reset_capacity(s);
coefs.resize(s);
}

std::size_t getBufferSize() const {
return static_cast<std::size_t>(coefs.size());
std::int64_t getBufferSize() const {
return static_cast<std::int64_t>(coefs.size());
}

void setElement(const std::size_t &rank, const coefT &coef) {
Expand Down Expand Up @@ -219,7 +220,7 @@ Value SetElement<sigT, coefT>::doExecute() {
FIRFilter<sigT, coefT> &entity =
static_cast<FIRFilter<sigT, coefT> &>(owner());
std::vector<Value> values = getParameterValues();
std::size_t rank = values[0].value();
std::uint64_t rank = values[0].value();
coefT coef = values[1].value();
entity.setElement(rank, coef);
return Value();
Expand All @@ -235,7 +236,7 @@ Value GetElement<sigT, coefT>::doExecute() {
FIRFilter<sigT, coefT> &entity =
static_cast<FIRFilter<sigT, coefT> &>(owner());
std::vector<Value> values = getParameterValues();
std::size_t rank = values[0].value();
std::uint64_t rank = values[0].value();
return Value(entity.getElement(rank));
}
} // namespace command
Expand Down
31 changes: 9 additions & 22 deletions include/sot/core/integrator.hh
Original file line number Diff line number Diff line change
Expand Up @@ -38,30 +38,14 @@
#include <dynamic-graph/signal-ptr.h>
#include "sot/core/periodic-call.hh"

namespace dg = dynamicgraph;

namespace dynamicgraph {
namespace sot {
namespace internal {
class Signal : public ::dynamicgraph::Signal<Vector, sigtime_t> {
protected:
enum SignalType { CONSTANT, REFERENCE, REFERENCE_NON_CONST, FUNCTION };
static const SignalType SIGNAL_TYPE_DEFAULT = CONSTANT;

const Vector *Treference;
Vector *TreferenceNonConst;
boost::function2<Vector &, Vector &, sigtime_t> Tfunction;

bool keepReference;
const static bool KEEP_REFERENCE_DEFAULT = false;

public:
#ifdef HAVE_LIBBOOST_THREAD
typedef boost::try_mutex Mutex;
typedef boost::lock_error MutexError;
#else
typedef size_type *Mutex;
typedef size_type *MutexError;
#endif

protected:
Mutex *providerMutex;
using SignalBase<sigtime_t>::signalTime;
Expand All @@ -81,10 +65,13 @@ class Signal : public ::dynamicgraph::Signal<Vector, sigtime_t> {

/* --- Generic Set function --- */
virtual void setConstant(const Vector &t);
virtual void setReference(const Vector *t, Mutex *mutexref = NULL);
virtual void setReferenceNonConstant(Vector *t, Mutex *mutexref = NULL);
virtual void setFunction(boost::function2<Vector &, Vector &, sigtime_t> t,
Mutex *mutexref = NULL);
virtual void setReference(
const Vector *t, dg::Signal<Vector, sigtime_t>::Mutex *mutexref = NULL);
virtual void setReferenceNonConstant(
Vector *t, dg::Signal<Vector, sigtime_t>::Mutex *mutexref = NULL);
virtual void setFunction(
boost::function2<Vector &, Vector &, sigtime_t> t,
dg::Signal<Vector, sigtime_t>::Mutex *mutexref = NULL);

/* --- Signal computation --- */
virtual const Vector &access(const sigtime_t &t);
Expand Down
3 changes: 2 additions & 1 deletion include/sot/core/matrix-constant.hh
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
/* Matrix */
#include <dynamic-graph/linear-algebra.h>

#include <cstdint>
/* --------------------------------------------------------------------- */
/* --- MATRIX ---------------------------------------------------------- */
/* --------------------------------------------------------------------- */
Expand All @@ -32,7 +33,7 @@ class MatrixConstant : public Entity {
static const std::string CLASS_NAME;
virtual const std::string &getClassName(void) const { return CLASS_NAME; }

size_type rows, cols;
std::int64_t rows, cols;
double color;

void setValue(const dynamicgraph::Matrix &inValue);
Expand Down
5 changes: 4 additions & 1 deletion include/sot/core/reader.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,14 @@
/* --- INCLUDE --------------------------------------------------------- */
/* --------------------------------------------------------------------- */

#include <cstdint>

/* Matrix */
#include <dynamic-graph/linear-algebra.h>

/* STD */
#include <boost/function.hpp>
#include <cstdint>
#include <fstream>
#include <list>
#include <string>
Expand Down Expand Up @@ -82,7 +85,7 @@ class SOTREADER_EXPORT sotReader : public Entity {
const std::size_t time);
dynamicgraph::Matrix &getNextMatrix(dynamicgraph::Matrix &res,
const std::size_t time);
void resize(const size_type &nbRow, const size_type &nbCol);
void resize(const std::int64_t &nbRow, const std::int64_t &nbCol);

public:
/* --- PARAMS --- */
Expand Down
4 changes: 3 additions & 1 deletion include/sot/core/segment.hh
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@
#ifndef SOT_CORE_SEGMENT_HH
#define SOT_CORE_SEGMENT_HH

#include <cstdint>

#include <sot/core/config.hh>
#include <dynamic-graph/entity.h>
#include <dynamic-graph/signal-ptr.t.cpp>
Expand All @@ -43,7 +45,7 @@ class SOT_CORE_DLLAPI Segment : public Entity {
static const std::string CLASS_NAME;
virtual const std::string& getClassName() const { return CLASS_NAME; }
// Set the range of input vector that is provided as output.
void setRange(const size_type& i0, const size_type& length) {
void setRange(const std::int64_t& i0, const std::int64_t& length) {
range_ = std::make_pair(i0, length);
}

Expand Down
4 changes: 2 additions & 2 deletions include/sot/core/smooth-reach.hh
Original file line number Diff line number Diff line change
Expand Up @@ -68,12 +68,12 @@ class SOTSMOOTHREACH_EXPORT SmoothReach : public dynamicgraph::Entity {
dynamicgraph::Vector &goalSOUT_function(dynamicgraph::Vector &goal,
const sigtime_t &time);

void set(const dynamicgraph::Vector &goal, const size_type &length);
void set(const dynamicgraph::Vector &goal, const std::int64_t &length);
const dynamicgraph::Vector &getGoal(void);
const size_type &getLength(void);
const size_type &getStart(void);

void setSmoothing(const size_type &mode, const double &param);
void setSmoothing(const std::int64_t &mode, const double &param);

public: /* --- PARAMS --- */
virtual void display(std::ostream &os) const;
Expand Down
6 changes: 4 additions & 2 deletions include/sot/core/sot.hh
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@
#ifndef __SOT_SOT_HH
#define __SOT_SOT_HH

#include <cstdint>

/* --------------------------------------------------------------------- */
/* --- INCLUDE --------------------------------------------------------- */
/* --------------------------------------------------------------------- */
Expand Down Expand Up @@ -148,8 +150,8 @@ class SOTSOT_CORE_EXPORT Sot : public Entity {

/*! \brief This method defines the part of the state vector
which correspond to the free flyer of the robot. */
virtual void defineNbDof(const size_type &nbDof);
virtual const size_type &getNbDof() const { return nbJoints; }
virtual void defineNbDof(const std::int64_t &nbDof);
virtual const std::int64_t &getNbDof() const { return nbJoints; }

/*! @} */
public: /* --- CONTROL --- */
Expand Down
9 changes: 5 additions & 4 deletions include/sot/core/switch.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,8 @@ class SOT_CORE_DLLAPI Switch : public VariadicAbstract<Value, Value, Time> {

Switch(const std::string &name)
: Base(name, CLASS_NAME),
selectionSIN(NULL, "Switch(" + name + ")::input(size_type)::selection"),
selectionSIN(NULL,
"Switch(" + name + ")::input(std::int64_t)::selection"),
boolSelectionSIN(NULL,
"Switch(" + name + ")::input(bool)::boolSelection") {
this->signalRegistration(selectionSIN << boolSelectionSIN);
Expand All @@ -47,7 +48,7 @@ class SOT_CORE_DLLAPI Switch : public VariadicAbstract<Value, Value, Time> {
"\n"
" Get number of input signals\n";
this->addCommand("getSignalNumber",
new command::Getter<Base, size_type>(
new command::Getter<Base, std::int64_t>(
*this, &Base::getSignalNumber, docstring));
}

Expand All @@ -58,7 +59,7 @@ class SOT_CORE_DLLAPI Switch : public VariadicAbstract<Value, Value, Time> {
return "Dynamically select a given signal based on a input information.\n";
}

SignalPtr<size_type, Time> selectionSIN;
SignalPtr<std::int64_t, Time> selectionSIN;
SignalPtr<bool, Time> boolSelectionSIN;

private:
Expand All @@ -73,7 +74,7 @@ class SOT_CORE_DLLAPI Switch : public VariadicAbstract<Value, Value, Time> {
if (sel < 0 || sel >= size_type(this->signalsIN.size()))
throw std::runtime_error("Signal selection is out of range.");

ret = this->signalsIN[sel]->access(time);
ret = this->signalsIN[static_cast<std::size_t>(sel)]->access(time);
return ret;
}
};
Expand Down
13 changes: 8 additions & 5 deletions include/sot/core/variadic-op.hh
Original file line number Diff line number Diff line change
Expand Up @@ -86,11 +86,12 @@ class VariadicAbstract : public Entity {
signalsIN.pop_back();
}

void setSignalNumber(const size_type &n) {
void setSignalNumber(const std::int64_t &n) {
assert(n >= 0);
const std::size_t oldSize = signalsIN.size();
for (std::size_t i = n; i < oldSize; ++i) _removeSignal(i);
signalsIN.resize(n, NULL);
for (std::size_t i = static_cast<std::size_t>(n); i < oldSize; ++i)
_removeSignal(i);
signalsIN.resize(static_cast<std::size_t>(n), NULL);
// names.resize(n);

for (std::size_t i = oldSize; i < (std::size_t)n; ++i) {
Expand All @@ -106,12 +107,14 @@ class VariadicAbstract : public Entity {
updateSignalNumber(n);
}

size_type getSignalNumber() const { return (size_type)signalsIN.size(); }
std::int64_t getSignalNumber() const {
return static_cast<std::int64_t>(signalsIN.size());
}

signal_t *getSignalIn(size_type i) {
if (i < 0 || i >= (size_type)signalsIN.size())
throw std::out_of_range("Wrong signal index");
return signalsIN[i];
return signalsIN[static_cast<std::size_t>(i)];
}

protected:
Expand Down
3 changes: 2 additions & 1 deletion include/sot/core/vector-constant.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
/* Matrix */
#include <dynamic-graph/linear-algebra.h>

#include <cstdint>
/* --------------------------------------------------------------------- */
/* --- VECTOR ---------------------------------------------------------- */
/* --------------------------------------------------------------------- */
Expand All @@ -30,7 +31,7 @@ class Resize;

class VectorConstant : public Entity {
friend class command::vectorConstant::Resize;
size_type rows;
std::int64_t rows;

public:
static const std::string CLASS_NAME;
Expand Down
Loading