From 85a651e27ee08fa2670d9b6d173da26bf72e4a66 Mon Sep 17 00:00:00 2001 From: SimonRohou Date: Wed, 10 Feb 2021 11:12:26 +0100 Subject: [PATCH] [all] codac::Vector/Function/Matrix/Ctc (using ibex) --- .travis.yml | 4 ++-- .../manual/02-variables/02-var-dynamic.rst | 2 +- .../04-static-contractors/01-ctc-function.rst | 8 +++---- .../04-static-contractors/03-ctc-polar.rst | 2 +- .../manual/08-going-further/03-pavings.rst | 2 +- doc/doc/tutorial/04-own-contractor/index.rst | 4 ++-- .../05_dyn_rangebearing.cpp | 1 - make.sh | 2 +- python/codac_py.cpp | 2 +- python/pyIbex_type_caster.h | 12 +++++----- .../contractors/static/codac_py_CtcDist.cpp | 2 +- .../trajectory/codac_py_TrajectoryVector.cpp | 10 ++++----- python/src/robotics/codac_py_TPlane.cpp | 2 +- src/3rd/capd/codac_capd_integrateODE.h | 6 ++--- src/3rd/pyibex/pyibex_Catan2.h | 5 ++--- src/3rd/pyibex/pyibex_CtcPolar.h | 4 +--- src/core/CMakeLists.txt | 17 +++++--------- src/core/arithmetic/codac_traj_arithmetic.h | 19 ++++++++-------- src/core/cn/codac_Contractor.h | 8 +++---- src/core/cn/codac_ContractorNetwork.h | 10 ++++----- src/core/cn/codac_Domain.h | 8 +++---- src/core/contractors/dyn/codac_CtcLinobs.h | 16 +++++++------- src/core/contractors/dyn/codac_CtcLohner.cpp | 20 ++++++++--------- src/core/contractors/dyn/codac_CtcLohner.h | 4 ++-- src/core/contractors/dyn/codac_CtcPicard.h | 2 +- src/core/contractors/dyn/codac_CtcStatic.h | 6 ++--- src/core/contractors/static/codac_Ctc.h | 22 +++++++++++++++++++ src/core/contractors/static/codac_CtcDist.h | 4 ++-- .../contractors/static/codac_CtcFunction.cpp | 1 - .../contractors/static/codac_CtcFunction.h | 10 ++++----- src/core/domains/tube/codac_TubeVector.h | 4 ++-- src/core/functions/codac_Function.h | 22 +++++++++++++++++++ src/core/functions/codac_TFunction.h | 12 +++++----- src/core/geometry/codac_ConvexPolygon.h | 2 +- src/core/geometry/codac_Edge.h | 4 ++-- src/core/geometry/codac_GrahamScan.h | 12 +++++----- src/core/geometry/codac_Point.h | 14 ++++++------ src/core/geometry/codac_Polygon.h | 10 ++++----- src/core/paving/codac_ConnectedSubset.h | 2 +- src/core/paving/codac_SIVIAPaving.h | 4 ++-- .../codac_serialize_trajectories.cpp | 2 +- src/core/tools/codac_Eigen.cpp | 8 +++---- src/core/tools/codac_Eigen.h | 10 ++++----- src/core/variables/real/codac_Matrix.h | 22 +++++++++++++++++++ src/core/variables/real/codac_Vector.h | 22 +++++++++++++++++++ .../trajectory/codac_TrajectoryVector.h | 20 ++++++++--------- .../codac_TrajectoryVector_operators.cpp | 2 +- src/robotics/contractors/codac_CtcConstell.h | 4 ++-- src/robotics/data/codac_DataLoader.h | 6 ++--- src/robotics/graphics/codac_VIBesFigMap.h | 14 ++++++------ src/robotics/objects/codac_Beacon.h | 7 +++--- tests/catch/catch_interval.hpp | 13 ++++++----- 52 files changed, 256 insertions(+), 175 deletions(-) create mode 100644 src/core/contractors/static/codac_Ctc.h create mode 100644 src/core/functions/codac_Function.h create mode 100644 src/core/variables/real/codac_Matrix.h create mode 100644 src/core/variables/real/codac_Vector.h diff --git a/.travis.yml b/.travis.yml index 79cb4b73..4fdb7b68 100644 --- a/.travis.yml +++ b/.travis.yml @@ -429,7 +429,7 @@ script: - make install #- cd python/python_package #- /usr/bin/python3.5 setup.py develop --user - #- /usr/bin/python3.5 pycodac/tests/test_arithmetic.py + #- /usr/bin/python3.5 pyibex/tests/test_arithmetic.py #- cd ../../ # Building the examples @@ -480,7 +480,7 @@ script: - make install #- cd python/python_package #- /usr/bin/python3.5 setup.py develop --user - #- /usr/bin/python3.5 pycodac/tests/test_arithmetic.py + #- /usr/bin/python3.5 pyibex/tests/test_arithmetic.py #- cd ../../ # Building the examples diff --git a/doc/doc/manual/02-variables/02-var-dynamic.rst b/doc/doc/manual/02-variables/02-var-dynamic.rst index a12e2f7d..53fd9992 100644 --- a/doc/doc/manual/02-variables/02-var-dynamic.rst +++ b/doc/doc/manual/02-variables/02-var-dynamic.rst @@ -448,7 +448,7 @@ Next pages will present several methods to use *tubes* that are envelopes of tra .. rubric:: Footnotes -.. [#f1] In Codac, a ``codac::TFunction`` is the extension of IBEX's ``ibex::Function`` objects, for the dynamical case (see more `about IBEX's functions `_). +.. [#f1] In Codac, a ``codac::TFunction`` is the extension of IBEX's ``Function`` objects, for the dynamical case (see more `about IBEX's functions `_). .. admonition:: Technical documentation diff --git a/doc/doc/manual/04-static-contractors/01-ctc-function.rst b/doc/doc/manual/04-static-contractors/01-ctc-function.rst index dc34ae80..29f27ced 100644 --- a/doc/doc/manual/04-static-contractors/01-ctc-function.rst +++ b/doc/doc/manual/04-static-contractors/01-ctc-function.rst @@ -148,9 +148,9 @@ The boxes are contracted in order to remove some vectors that are not consistent .. #include .. #include -.. #include "ibex_CtcHC4.h" +.. #include "codac_CtcHC4.h" .. #include "ibex_SystemFactory.h" -.. #include "ibex_Ctc3BCid.h" +.. #include "codac_Ctc3BCid.h" .. .. using namespace std; .. using namespace codac; @@ -159,7 +159,7 @@ The boxes are contracted in order to remove some vectors that are not consistent .. int main() .. { .. SIVIAPaving p({{-3.,3.},{-3.,3.}}); -.. p.compute(ibex::Function("x1", "x2", "x1*cos(x1-x2)*sin(x1)+x2"), {{0.}}, 0.01); +.. p.compute(Function("x1", "x2", "x1*cos(x1-x2)*sin(x1)+x2"), {{0.}}, 0.01); .. CtcFunction ctc_f(Function("x1", "x2", "x1*cos(x1-x2)*sin(x1)+x2")); .. .. vibes::beginDrawing(); @@ -198,7 +198,7 @@ Going further This ``CtcFunction`` class is a generic shortcut to deal with :math:`\mathbf{f}(\mathbf{x})=\mathbf{0}` or :math:`\mathbf{f}(\mathbf{x})\in[\mathbf{y}]`. However, several algorithms exist to optimally deal with different classes of problems. A list of static contractors is provided in the IBEX library: `see more `_. The user is invited to use an appropriate tool to deal with the constraint at stake. -The IBEX contractor behind ``CtcFunction`` is a ``ibex::CtcFwdBwd`` coupled with a ``ibex::Ctc3BCid``. +The IBEX contractor behind ``CtcFunction`` is a ``CtcFwdBwd`` coupled with a ``Ctc3BCid``. .. admonition:: Technical documentation diff --git a/doc/doc/manual/04-static-contractors/03-ctc-polar.rst b/doc/doc/manual/04-static-contractors/03-ctc-polar.rst index f23ace5b..8a7bdef5 100644 --- a/doc/doc/manual/04-static-contractors/03-ctc-polar.rst +++ b/doc/doc/manual/04-static-contractors/03-ctc-polar.rst @@ -103,7 +103,7 @@ Calls to :math:`\mathcal{C}_{\textrm{polar}}` will allow the contraction of the // ... - pyibex::CtcPolar ctc_polar; + pyCtcPolar ctc_polar; ctc_polar.contract(b1[0], b1[1], d1, theta1); ctc_polar.contract(b2[0], b2[1], d2, theta2); diff --git a/doc/doc/manual/08-going-further/03-pavings.rst b/doc/doc/manual/08-going-further/03-pavings.rst index 93639d27..6f8fe8bc 100644 --- a/doc/doc/manual/08-going-further/03-pavings.rst +++ b/doc/doc/manual/08-going-further/03-pavings.rst @@ -45,7 +45,7 @@ SIVIAPaving .. code-tab:: c++ SIVIAPaving p({{-3.,3.},{-3.,3.}}); - p.compute(ibex::Function("x", "y", "x*cos(x-y)*sin(x)+y"), + p.compute(Function("x", "y", "x*cos(x-y)*sin(x)+y"), {{-0.35,0.35}}, 0.01); diff --git a/doc/doc/tutorial/04-own-contractor/index.rst b/doc/doc/tutorial/04-own-contractor/index.rst index 62e77ca0..c98b9a5e 100644 --- a/doc/doc/tutorial/04-own-contractor/index.rst +++ b/doc/doc/tutorial/04-own-contractor/index.rst @@ -117,12 +117,12 @@ where :math:`\bigsqcup`, called *squared union*, returns the smallest box enclos .. code-tab:: cpp - class MyCtc : public ibex::Ctc + class MyCtc : public Ctc { public: MyCtc(const std::vector& M_) - : ibex::Ctc(2), // the contractor acts on 2d boxes + : Ctc(2), // the contractor acts on 2d boxes M(M_) // attribute needed later on for the contraction { diff --git a/examples/tuto/05_dyn_rangebearing/05_dyn_rangebearing.cpp b/examples/tuto/05_dyn_rangebearing/05_dyn_rangebearing.cpp index 2ddaf85d..217996bf 100644 --- a/examples/tuto/05_dyn_rangebearing/05_dyn_rangebearing.cpp +++ b/examples/tuto/05_dyn_rangebearing/05_dyn_rangebearing.cpp @@ -16,7 +16,6 @@ using namespace std; using namespace codac; -using namespace pyibex; int main() { diff --git a/make.sh b/make.sh index 42d2770f..4a2383c4 100755 --- a/make.sh +++ b/make.sh @@ -44,7 +44,7 @@ fi cmake -DBUILD_TESTS=OFF -DWITH_TUBE_TREE="${WITH_TUBE_TREE}" .. fi - make + make -j make api make doc cd .. diff --git a/python/codac_py.cpp b/python/codac_py.cpp index 179da1ae..d456bdb4 100644 --- a/python/codac_py.cpp +++ b/python/codac_py.cpp @@ -9,7 +9,7 @@ * the GNU Lesser General Public License (LGPL). */ -#include "ibex_Ctc.h" +#include "codac_Ctc.h" #include "codac_DynCtc.h" #include "codac_TFnc.h" #include "codac_VIBesFig.h" diff --git a/python/pyIbex_type_caster.h b/python/pyIbex_type_caster.h index 1e7cf1d7..4562ed9f 100644 --- a/python/pyIbex_type_caster.h +++ b/python/pyIbex_type_caster.h @@ -1,9 +1,9 @@ #ifndef __PYIBEX_TYPE_CASTER_H__ #define __PYIBEX_TYPE_CASTER_H__ -#include "ibex_Vector.h" +#include "codac_Vector.h" #include "ibex_Array.h" -#include "ibex_Ctc.h" +#include "codac_Ctc.h" #include NAMESPACE_BEGIN(pybind11) @@ -12,11 +12,11 @@ NAMESPACE_BEGIN(detail) using ibex::Vector; using ibex::Array; -template <> struct type_caster { +template <> struct type_caster { public: - PYBIND11_TYPE_CASTER(ibex::Vector, _("Vector")); + PYBIND11_TYPE_CASTER(Vector, _("Vector")); - type_caster() : value(1) { } + type_caster() : value(1) { } bool load(handle src_hdl, bool convert) { PyObject *src = src_hdl.ptr(); if (!PyList_Check(src) && !PyTuple_Check(src)) @@ -37,7 +37,7 @@ template <> struct type_caster { return true; } - static handle cast(const ibex::Vector &src, return_value_policy policy, handle parent) { + static handle cast(const Vector &src, return_value_policy policy, handle parent) { list l(src.size()); for (int i = 0; i < src.size(); i++){ diff --git a/python/src/core/contractors/static/codac_py_CtcDist.cpp b/python/src/core/contractors/static/codac_py_CtcDist.cpp index 82212e46..b141bd64 100644 --- a/python/src/core/contractors/static/codac_py_CtcDist.cpp +++ b/python/src/core/contractors/static/codac_py_CtcDist.cpp @@ -27,7 +27,7 @@ using namespace pybind11::literals; void export_CtcDist(py::module& m) { - py::class_ ctc_dist(m, "CtcDist", CTCDIST_MAIN); + py::class_ ctc_dist(m, "CtcDist", CTCDIST_MAIN); ctc_dist .def(py::init<>(), diff --git a/python/src/core/variables/trajectory/codac_py_TrajectoryVector.cpp b/python/src/core/variables/trajectory/codac_py_TrajectoryVector.cpp index 5d2aab4c..a9e4939c 100644 --- a/python/src/core/variables/trajectory/codac_py_TrajectoryVector.cpp +++ b/python/src/core/variables/trajectory/codac_py_TrajectoryVector.cpp @@ -267,15 +267,15 @@ void export_TrajectoryVector(py::module& m) .def("__rmul__", [](const TrajectoryVector& y, double x) { return x*y; }) .def("__rmul__", [](const TrajectoryVector& y, const Trajectory& x) { return x*y; }) - // todo const TrajectoryVector operator*(const Trajectory& x, const ibex::Vector& y); - // todo const TrajectoryVector operator*(const ibex::Matrix& x, const TrajectoryVector& y); + // todo const TrajectoryVector operator*(const Trajectory& x, const Vector& y); + // todo const TrajectoryVector operator*(const Matrix& x, const TrajectoryVector& y); .def("__truediv__", [](const TrajectoryVector& x, double y) { return x/y; }) .def("__truediv__", [](const TrajectoryVector& x, const Trajectory& y) { return x/y; }) - // todo const TrajectoryVector operator/(const ibex::Vector& x, const Trajectory& y); + // todo const TrajectoryVector operator/(const Vector& x, const Trajectory& y); - // todo const TrajectoryVector vecto_product(const TrajectoryVector& x, const ibex::Vector& y); - // todo const TrajectoryVector vecto_product(const ibex::Vector& x, const TrajectoryVector& y); + // todo const TrajectoryVector vecto_product(const TrajectoryVector& x, const Vector& y); + // todo const TrajectoryVector vecto_product(const Vector& x, const TrajectoryVector& y); ; } diff --git a/python/src/robotics/codac_py_TPlane.cpp b/python/src/robotics/codac_py_TPlane.cpp index 5419da80..f7505e39 100644 --- a/python/src/robotics/codac_py_TPlane.cpp +++ b/python/src/robotics/codac_py_TPlane.cpp @@ -39,7 +39,7 @@ void export_TPlane(py::module& m) "precision"_a, "p"_a, "v"_a) .def("compute_proofs", (void (TPlane::*)(const TubeVector&,const TubeVector&))&TPlane::compute_proofs, - TPLANE_VOID_COMPUTE_PROOFS_INTERVALVECTORPINTERVALVECTORB, + TPLANE_VOID_COMPUTE_PROOFS_TUBEVECTOR_TUBEVECTOR, "p"_a, "v"_a) .def("nb_loops_detections", &TPlane::nb_loops_detections, diff --git a/src/3rd/capd/codac_capd_integrateODE.h b/src/3rd/capd/codac_capd_integrateODE.h index f0037d20..e5477148 100644 --- a/src/3rd/capd/codac_capd_integrateODE.h +++ b/src/3rd/capd/codac_capd_integrateODE.h @@ -15,7 +15,7 @@ #include "codac_TubeVector.h" #include "codac_TFunction.h" #include "codac_IntervalVector.h" -#include "ibex_Function.h" +#include "codac_Function.h" namespace codac { @@ -25,7 +25,7 @@ namespace codac * \brief Integrates the autonomous ODE \f$\dot{\mathbf{x}}=\mathbf{f}(\mathbf{x})\f$ using CAPD. * * \param tdomain temporal domain \f$[t_0,t_f]\f$ - * \param f the function \f$\mathbf{f}\f$ (defined with a `ibex::Function` object) + * \param f the function \f$\mathbf{f}\f$ (defined with a `Function` object) * \param x0 the initial condition \f$\mathbf{x}_0\f$ at \f$t_0\f$ * \param tube_dt sampling value \f$\delta\f$ for the temporal discretization of the resulting tube * \param capd_order (optional) order of the integration method @@ -33,7 +33,7 @@ namespace codac * \return TubeVector enclosing the solution */ TubeVector CAPD_integrateODE( - const Interval& tdomain, const ibex::Function& f, const IntervalVector& x0, + const Interval& tdomain, const Function& f, const IntervalVector& x0, double tube_dt = 0., int capd_order = 20, double capd_dt = 0.); // Non autonomous diff --git a/src/3rd/pyibex/pyibex_Catan2.h b/src/3rd/pyibex/pyibex_Catan2.h index 2c3b6976..05f0d29c 100644 --- a/src/3rd/pyibex/pyibex_Catan2.h +++ b/src/3rd/pyibex/pyibex_Catan2.h @@ -13,12 +13,11 @@ #ifndef __IBEX_CTC_ANGLE_H__ #define __IBEX_CTC_ANGLE_H__ -#include "codac_IntervalVector.h" -#include "ibex_Ctc.h" +#include +#include #include // using namespace std; -using ibex::Ctc; using ibex::bwd_imod; namespace codac { diff --git a/src/3rd/pyibex/pyibex_CtcPolar.h b/src/3rd/pyibex/pyibex_CtcPolar.h index c2f71bbd..228dac5f 100644 --- a/src/3rd/pyibex/pyibex_CtcPolar.h +++ b/src/3rd/pyibex/pyibex_CtcPolar.h @@ -16,9 +16,7 @@ #include #include -#include "ibex_Ctc.h" - -using ibex::Ctc; +#include using namespace std; diff --git a/src/core/CMakeLists.txt b/src/core/CMakeLists.txt index 771bee61..783217b4 100644 --- a/src/core/CMakeLists.txt +++ b/src/core/CMakeLists.txt @@ -2,7 +2,8 @@ # Codac - cmake configuration file # ================================================================== - list(APPEND SRC ${CMAKE_CURRENT_SOURCE_DIR}/functions/codac_TFnc.h + list(APPEND SRC ${CMAKE_CURRENT_SOURCE_DIR}/functions/codac_Function.h + ${CMAKE_CURRENT_SOURCE_DIR}/functions/codac_TFnc.h ${CMAKE_CURRENT_SOURCE_DIR}/functions/codac_TFnc.cpp ${CMAKE_CURRENT_SOURCE_DIR}/functions/codac_TFunction.h ${CMAKE_CURRENT_SOURCE_DIR}/functions/codac_TFunction.cpp @@ -72,6 +73,8 @@ ${CMAKE_CURRENT_SOURCE_DIR}/domains/slice/codac_Slice.cpp ${CMAKE_CURRENT_SOURCE_DIR}/domains/slice/codac_Slice_polygon.cpp ${CMAKE_CURRENT_SOURCE_DIR}/domains/slice/codac_Slice_operators.cpp + ${CMAKE_CURRENT_SOURCE_DIR}/variables/real/codac_Vector.h + ${CMAKE_CURRENT_SOURCE_DIR}/variables/real/codac_Matrix.h ${CMAKE_CURRENT_SOURCE_DIR}/variables/trajectory/codac_RandTrajectory.h ${CMAKE_CURRENT_SOURCE_DIR}/variables/trajectory/codac_RandTrajectory.cpp ${CMAKE_CURRENT_SOURCE_DIR}/variables/trajectory/codac_Trajectory.h @@ -92,6 +95,7 @@ ${CMAKE_CURRENT_SOURCE_DIR}/serialize/codac_serialize_tubes.cpp ${CMAKE_CURRENT_SOURCE_DIR}/serialize/codac_serialize_intervals.h ${CMAKE_CURRENT_SOURCE_DIR}/serialize/codac_serialize_intervals.cpp + ${CMAKE_CURRENT_SOURCE_DIR}/contractors/static/codac_Ctc.h ${CMAKE_CURRENT_SOURCE_DIR}/contractors/static/codac_CtcDist.h ${CMAKE_CURRENT_SOURCE_DIR}/contractors/static/codac_CtcDist.cpp ${CMAKE_CURRENT_SOURCE_DIR}/contractors/static/codac_CtcFunction.h @@ -148,6 +152,7 @@ ${CMAKE_CURRENT_SOURCE_DIR}/domains/interval ${CMAKE_CURRENT_SOURCE_DIR}/domains/tube ${CMAKE_CURRENT_SOURCE_DIR}/domains/slice + ${CMAKE_CURRENT_SOURCE_DIR}/variables/real ${CMAKE_CURRENT_SOURCE_DIR}/variables/trajectory ${CMAKE_CURRENT_SOURCE_DIR}/exceptions ${CMAKE_CURRENT_SOURCE_DIR}/serialize @@ -183,17 +188,7 @@ file(WRITE ${CODAC_MAIN_HEADER} "/* This file is generated by CMake */\n\n") file(APPEND ${CODAC_MAIN_HEADER} "#ifndef __CODAC_H__\n#define __CODAC_H__\n\n") # Simplifying access to frequently used items of IBEX - file(APPEND ${CODAC_MAIN_HEADER} "#include \n") - file(APPEND ${CODAC_MAIN_HEADER} "#include \n") - file(APPEND ${CODAC_MAIN_HEADER} "#include \n") - file(APPEND ${CODAC_MAIN_HEADER} "#include \n") file(APPEND ${CODAC_MAIN_HEADER} "\n") - file(APPEND ${CODAC_MAIN_HEADER} "namespace codac\n{\n") - file(APPEND ${CODAC_MAIN_HEADER} " using ibex::Vector;\n") - file(APPEND ${CODAC_MAIN_HEADER} " using ibex::Matrix;\n") - file(APPEND ${CODAC_MAIN_HEADER} " using ibex::Ctc;\n") - file(APPEND ${CODAC_MAIN_HEADER} " using ibex::Function;\n") - file(APPEND ${CODAC_MAIN_HEADER} "}\n\n") file(APPEND ${CODAC_MAIN_HEADER} "#include \n") # todo: clean this organization file(APPEND ${CODAC_MAIN_HEADER} "#include \n") # todo: clean this organization foreach(header_path ${HDR}) diff --git a/src/core/arithmetic/codac_traj_arithmetic.h b/src/core/arithmetic/codac_traj_arithmetic.h index 3efe81c6..7ec9e4a0 100644 --- a/src/core/arithmetic/codac_traj_arithmetic.h +++ b/src/core/arithmetic/codac_traj_arithmetic.h @@ -14,6 +14,7 @@ #include "codac_Trajectory.h" #include "codac_TrajectoryVector.h" +#include "codac_Matrix.h" namespace codac { @@ -287,14 +288,14 @@ namespace codac * \param y * \return TrajectoryVector output */ - const TrajectoryVector operator+(const TrajectoryVector& x, const ibex::Vector& y); + const TrajectoryVector operator+(const TrajectoryVector& x, const Vector& y); /** \brief \f$\mathbf{x}+\mathbf{y}(\cdot)\f$ * \param x * \param y * \return TrajectoryVector output */ - const TrajectoryVector operator+(const ibex::Vector& x, const TrajectoryVector& y); + const TrajectoryVector operator+(const Vector& x, const TrajectoryVector& y); /** \brief \f$-\mathbf{x}(\cdot)\f$ @@ -315,14 +316,14 @@ namespace codac * \param y * \return TrajectoryVector output */ - const TrajectoryVector operator-(const TrajectoryVector& x, const ibex::Vector& y); + const TrajectoryVector operator-(const TrajectoryVector& x, const Vector& y); /** \brief \f$\mathbf{x}-\mathbf{y}(\cdot)\f$ * \param x * \param y * \return TrajectoryVector output */ - const TrajectoryVector operator-(const ibex::Vector& x, const TrajectoryVector& y); + const TrajectoryVector operator-(const Vector& x, const TrajectoryVector& y); /** \brief \f$x\cdot\mathbf{y}(\cdot)\f$ @@ -344,14 +345,14 @@ namespace codac * \param y * \return TrajectoryVector output */ - const TrajectoryVector operator*(const Trajectory& x, const ibex::Vector& y); + const TrajectoryVector operator*(const Trajectory& x, const Vector& y); /** \brief \f$x(\cdot)\cdot\mathbf{y}\f$ * \param x * \param y * \return TrajectoryVector output */ - const TrajectoryVector operator*(const ibex::Matrix& x, const TrajectoryVector& y); + const TrajectoryVector operator*(const Matrix& x, const TrajectoryVector& y); /** \brief \f$\mathbf{x}(\cdot)/y\f$ @@ -373,7 +374,7 @@ namespace codac * \param y * \return TrajectoryVector output */ - const TrajectoryVector operator/(const ibex::Vector& x, const Trajectory& y); + const TrajectoryVector operator/(const Vector& x, const Trajectory& y); /** \brief \f$\mathbf{x}(\cdot)\times\mathbf{y}\f$ (or \f$\mathbf{x}(\cdot)\wedge\mathbf{y}\f$ in physics) @@ -381,14 +382,14 @@ namespace codac * \param y * \return TrajectoryVector output */ - const TrajectoryVector vecto_product(const TrajectoryVector& x, const ibex::Vector& y); + const TrajectoryVector vecto_product(const TrajectoryVector& x, const Vector& y); /** \brief \f$\mathbf{x}\times\mathbf{y}(\cdot)\f$ (or \f$\mathbf{x}\wedge\mathbf{y}(\cdot)\f$ in physics) * \param x * \param y * \return TrajectoryVector output */ - const TrajectoryVector vecto_product(const ibex::Vector& x, const TrajectoryVector& y); + const TrajectoryVector vecto_product(const Vector& x, const TrajectoryVector& y); /** \brief \f$\mid\mathbf{x}(\cdot)\mid\f$ diff --git a/src/core/cn/codac_Contractor.h b/src/core/cn/codac_Contractor.h index 93ffc72e..d4c5a142 100644 --- a/src/core/cn/codac_Contractor.h +++ b/src/core/cn/codac_Contractor.h @@ -14,7 +14,7 @@ #include #include -#include "ibex_Ctc.h" +#include "codac_Ctc.h" #include "codac_DynCtc.h" #include "codac_Domain.h" #include "codac_ContractorNetwork.h" @@ -38,7 +38,7 @@ namespace codac enum class Type { T_COMPONENT, T_EQUALITY, T_IBEX, T_CODAC }; Contractor(Type type, const std::vector& v_domains); - Contractor(ibex::Ctc& ctc, const std::vector& v_domains); + Contractor(Ctc& ctc, const std::vector& v_domains); Contractor(DynCtc& ctc, const std::vector& v_domains); Contractor(const Contractor& ac); ~Contractor(); @@ -46,7 +46,7 @@ namespace codac int id() const; Type type() const; - ibex::Ctc& ibex_ctc(); + Ctc& ibex_ctc(); DynCtc& codac_ctc(); bool is_active() const; @@ -72,7 +72,7 @@ namespace codac union { - std::reference_wrapper m_static_ctc; + std::reference_wrapper m_static_ctc; std::reference_wrapper m_dyn_ctc; }; diff --git a/src/core/cn/codac_ContractorNetwork.h b/src/core/cn/codac_ContractorNetwork.h index 77dca298..30f21f74 100644 --- a/src/core/cn/codac_ContractorNetwork.h +++ b/src/core/cn/codac_ContractorNetwork.h @@ -14,7 +14,7 @@ #include #include -#include "ibex_Ctc.h" +#include "codac_Ctc.h" #include "codac_DynCtc.h" #include "codac_Domain.h" #include "codac_Contractor.h" @@ -148,7 +148,7 @@ namespace codac * \param end_index last component index of the subvector to be returned * \return a reference to the created IntervalVector extracted from the Vector domain */ - IntervalVector& subvector(ibex::Vector& v, int start_index, int end_index); + IntervalVector& subvector(Vector& v, int start_index, int end_index); /** * \brief Creates a subvector of an IntervalVector domain @@ -176,10 +176,10 @@ namespace codac * \note If tubes are involved in the domain list, they must share the same slicing and tdomain. * The static contractor will be applied on each slice of these tubes. * - * \param static_ctc ibex::Ctc contractor object + * \param static_ctc Ctc contractor object * \param v_domains a vector of abstract domains (Interval, Slice, Tube, etc.) */ - void add(ibex::Ctc& static_ctc, const std::vector& v_domains); + void add(Ctc& static_ctc, const std::vector& v_domains); /** * \brief Adds to the graph a dynamic contractor (inherited from DynCtc class) with related Domains @@ -302,7 +302,7 @@ namespace codac * \param ctc static contractor (inherited from Ctc) to name * \param name string of characters */ - void set_name(ibex::Ctc& ctc, const std::string& name); + void set_name(Ctc& ctc, const std::string& name); /** * \brief Sets a string name for a given dynamic contractor diff --git a/src/core/cn/codac_Domain.h b/src/core/cn/codac_Domain.h index 1d49e2d8..19ad6ea4 100644 --- a/src/core/cn/codac_Domain.h +++ b/src/core/cn/codac_Domain.h @@ -45,8 +45,8 @@ namespace codac Domain(Interval& i, double& extern_d); Domain(Interval& i, Interval& extern_i); Domain(const Interval& i); - Domain(ibex::Vector& v); - // todo: ? Domain(const ibex::Vector& v); + Domain(Vector& v); + // todo: ? Domain(const Vector& v); Domain(IntervalVector& iv); Domain(const IntervalVector& iv); Domain(Slice& s); @@ -141,7 +141,7 @@ namespace codac { std::reference_wrapper m_ref_memory_d; std::reference_wrapper m_ref_memory_i; - std::reference_wrapper m_ref_memory_v; + std::reference_wrapper m_ref_memory_v; std::reference_wrapper m_ref_memory_iv; std::reference_wrapper m_ref_memory_s; std::reference_wrapper m_ref_memory_t; @@ -151,7 +151,7 @@ namespace codac // todo: update this: std::map m_map_data_s_lb, m_map_data_s_ub; - std::map m_map_data_lb, m_map_data_ub; + std::map m_map_data_lb, m_map_data_ub; Trajectory m_traj_lb, m_traj_ub; diff --git a/src/core/contractors/dyn/codac_CtcLinobs.h b/src/core/contractors/dyn/codac_CtcLinobs.h index 2f0ab8e8..3c5fc7bf 100644 --- a/src/core/contractors/dyn/codac_CtcLinobs.h +++ b/src/core/contractors/dyn/codac_CtcLinobs.h @@ -31,8 +31,8 @@ namespace codac /** * \brief Creates a contractor object \f$\mathcal{C}_\textrm{linobs}\f$ */ - // CtcLinobs(const ibex::Matrix& A, const ibex::Vector& b); // not yet available since auto evaluation of e^At not at hand - CtcLinobs(const ibex::Matrix& A, const ibex::Vector& b, IntervalMatrix (*exp_At)(const ibex::Matrix& A, const Interval& t)); + // CtcLinobs(const Matrix& A, const Vector& b); // not yet available since auto evaluation of e^At not at hand + CtcLinobs(const Matrix& A, const Vector& b, IntervalMatrix (*exp_At)(const Matrix& A, const Interval& t)); void contract(std::vector& v_domains); void contract(TubeVector& x, const Tube& u, TimePropag t_propa = TimePropag::FORWARD | TimePropag::BACKWARD); @@ -46,20 +46,20 @@ namespace codac void contract(std::vector& v_t, std::vector& v_y, TubeVector& x, const Tube& u, TimePropag t_propa = TimePropag::FORWARD | TimePropag::BACKWARD); void contract(std::vector& v_t, std::vector& v_y, TubeVector& x, const Tube& u, std::vector& v_p_k, TimePropag t_propa = TimePropag::FORWARD | TimePropag::BACKWARD); - ConvexPolygon polygon_envelope(const ConvexPolygon& p_k, double dt_k_kp1, const ibex::Matrix& A, const ibex::Vector& b, const Interval& u_k); + ConvexPolygon polygon_envelope(const ConvexPolygon& p_k, double dt_k_kp1, const Matrix& A, const Vector& b, const Interval& u_k); protected: - void ctc_fwd_gate(ConvexPolygon& p_k, const ConvexPolygon& p_km1, double dt_km1_k, const ibex::Matrix& A, const ibex::Vector& b, const Interval& u_km1); - void ctc_bwd_gate(ConvexPolygon& p_k, const ConvexPolygon& p_kp1, double dt_k_kp1, const ibex::Matrix& A, const ibex::Vector& b, const Interval& u_k); + void ctc_fwd_gate(ConvexPolygon& p_k, const ConvexPolygon& p_km1, double dt_km1_k, const Matrix& A, const Vector& b, const Interval& u_km1); + void ctc_bwd_gate(ConvexPolygon& p_k, const ConvexPolygon& p_kp1, double dt_k_kp1, const Matrix& A, const Vector& b, const Interval& u_k); protected: - const ibex::Matrix& m_A; - const ibex::Vector& m_b; - IntervalMatrix (*m_exp_At)(const ibex::Matrix& A, const Interval& t); + const Matrix& m_A; + const Vector& m_b; + IntervalMatrix (*m_exp_At)(const Matrix& A, const Interval& t); const int m_polygon_max_edges = 15; diff --git a/src/core/contractors/dyn/codac_CtcLohner.cpp b/src/core/contractors/dyn/codac_CtcLohner.cpp index 121efec2..aa9b8cb3 100644 --- a/src/core/contractors/dyn/codac_CtcLohner.cpp +++ b/src/core/contractors/dyn/codac_CtcLohner.cpp @@ -54,7 +54,7 @@ class LohnerAlgorithm { * \param contractions number of contractions of the global enclosure by the estimated local enclosure * \param eps inflation parameter for the global enclosure */ - LohnerAlgorithm(const ibex::Function *f, + LohnerAlgorithm(const Function *f, double h, bool forward, const IntervalVector &u0 = IntervalVector::empty(1), @@ -109,14 +109,14 @@ class LohnerAlgorithm { IntervalVector z; //!< Taylor-Lagrange remainder (order 2) IntervalVector r; //!< enclosure of uncertainties in the frame given by the matrix B IntervalVector u_tilde; //!< global enclosure - ibex::Matrix B, Binv; - ibex::Vector u_hat; //!< center of the box u - const ibex::Function *f; //!< litteral function of the system \f$\dot{\mathbf{x}}=\mathbf{f}(\mathbf{x})\f$ + Matrix B, Binv; + Vector u_hat; //!< center of the box u + const Function *f; //!< litteral function of the system \f$\dot{\mathbf{x}}=\mathbf{f}(\mathbf{x})\f$ }; // -- -LohnerAlgorithm::LohnerAlgorithm(const ibex::Function *f, +LohnerAlgorithm::LohnerAlgorithm(const Function *f, double h, bool forward, const IntervalVector &u0, @@ -130,8 +130,8 @@ LohnerAlgorithm::LohnerAlgorithm(const ibex::Function *f, u(u0), z(u0 - u0.mid()), r(z), - B(ibex::Matrix::eye(dim)), - Binv(ibex::Matrix::eye(dim)), + B(Matrix::eye(dim)), + Binv(Matrix::eye(dim)), u_hat(u0.mid()), f(f) {} @@ -144,8 +144,8 @@ const IntervalVector &LohnerAlgorithm::integrate(unsigned int steps, double H) { IntervalVector u_t = globalEnclosure(u, FWD); for (int j = 0; j < contractions; ++j) { z1 = 0.5 * h * h * f->jacobian(u_t) * f->eval_vector(u_t); - ibex::Vector m1 = z1.mid(); - IntervalMatrix A = ibex::Matrix::eye(dim) + h * direction * f->jacobian(u); + Vector m1 = z1.mid(); + IntervalMatrix A = Matrix::eye(dim) + h * direction * f->jacobian(u); Eigen::HouseholderQR qr(EigenHelpers::i2e((A * B).mid())); B1 = EigenHelpers::e2i(qr.householderQ()); B1inv = ibex::real_inverse(B1); @@ -188,7 +188,7 @@ const IntervalVector &LohnerAlgorithm::getGlobalEnclosure() const { return u_tilde; } -CtcLohner::CtcLohner(const ibex::Function &f, int contractions, double eps) +CtcLohner::CtcLohner(const Function &f, int contractions, double eps) : DynCtc(), m_f(f), contractions(contractions), diff --git a/src/core/contractors/dyn/codac_CtcLohner.h b/src/core/contractors/dyn/codac_CtcLohner.h index 1a16448e..7e38d3c4 100644 --- a/src/core/contractors/dyn/codac_CtcLohner.h +++ b/src/core/contractors/dyn/codac_CtcLohner.h @@ -35,7 +35,7 @@ class CtcLohner : public codac::DynCtc { * \param contractions number of contractions of the global enclosure by the estimated local enclosure * \param eps inflation parameter for the global enclosure */ - explicit CtcLohner(const ibex::Function &f, int contractions = 5, double eps = 0.1); + explicit CtcLohner(const Function &f, int contractions = 5, double eps = 0.1); /** * \brief Contracts the tube with respect to the specified differential constraint, either forward, backward (or both) in time @@ -63,7 +63,7 @@ class CtcLohner : public codac::DynCtc { void contract(std::vector &v_domains) override; protected: - ibex::Function m_f; //!< forward function + Function m_f; //!< forward function int contractions; //!< number of contractions of the global enclosure by the estimated local enclosure int dim; //!< dimension of the state vector double eps; //!< inflation parameter for the global enclosure diff --git a/src/core/contractors/dyn/codac_CtcPicard.h b/src/core/contractors/dyn/codac_CtcPicard.h index d9f6019f..6b6d967c 100644 --- a/src/core/contractors/dyn/codac_CtcPicard.h +++ b/src/core/contractors/dyn/codac_CtcPicard.h @@ -26,7 +26,7 @@ namespace codac { public: - CtcPicard(ibex::Function& f, float delta = 1.1); + CtcPicard(Function& f, float delta = 1.1); CtcPicard(TFnc& f, float delta = 1.1); ~CtcPicard(); diff --git a/src/core/contractors/dyn/codac_CtcStatic.h b/src/core/contractors/dyn/codac_CtcStatic.h index 1d81a570..d0ee86e2 100644 --- a/src/core/contractors/dyn/codac_CtcStatic.h +++ b/src/core/contractors/dyn/codac_CtcStatic.h @@ -12,7 +12,7 @@ #ifndef __CODAC_CTCSTATIC_H__ #define __CODAC_CTCSTATIC_H__ -#include "ibex_Ctc.h" +#include "codac_Ctc.h" #include "codac_DynCtc.h" #include "codac_Domain.h" @@ -35,7 +35,7 @@ namespace codac * \param dynamic_ctc if true, the contraction will include the * temporal tdomain as first dimension of the (n+1) box */ - CtcStatic(ibex::Ctc& ibex_ctc, bool dynamic_ctc = false); + CtcStatic(Ctc& ibex_ctc, bool dynamic_ctc = false); /* * \brief Contracts a set of abstract domains @@ -122,7 +122,7 @@ namespace codac protected: - ibex::Ctc& m_static_ctc; //!< related static contractor + Ctc& m_static_ctc; //!< related static contractor int m_dynamic_ctc; //!< specifies either the temporal tdomain is part of the contraction or not static const std::string m_ctc_name; //!< class name (mainly used for CN Exceptions) diff --git a/src/core/contractors/static/codac_Ctc.h b/src/core/contractors/static/codac_Ctc.h new file mode 100644 index 00000000..6a5c7ca1 --- /dev/null +++ b/src/core/contractors/static/codac_Ctc.h @@ -0,0 +1,22 @@ +/** + * \file + * Ctc class + * ---------------------------------------------------------------------------- + * \date 2021 + * \author Simon Rohou + * \copyright Copyright 2021 Codac Team + * \license This program is distributed under the terms of + * the GNU Lesser General Public License (LGPL). + */ + +#ifndef __CODAC_CTC_H__ +#define __CODAC_CTC_H__ + +#include "ibex_Ctc.h" + +namespace codac +{ + using ibex::Ctc; +} + +#endif \ No newline at end of file diff --git a/src/core/contractors/static/codac_CtcDist.h b/src/core/contractors/static/codac_CtcDist.h index 235d158f..df76e668 100644 --- a/src/core/contractors/static/codac_CtcDist.h +++ b/src/core/contractors/static/codac_CtcDist.h @@ -12,7 +12,7 @@ #ifndef __CODAC_CTCDIST_H__ #define __CODAC_CTCDIST_H__ -#include "ibex_Ctc.h" +#include "codac_Ctc.h" #include "codac_Interval.h" #include "codac_IntervalVector.h" @@ -22,7 +22,7 @@ namespace codac * \class CtcDist * \brief Distance constraint between two 2d vectors. */ - class CtcDist : public ibex::Ctc + class CtcDist : public Ctc { public: diff --git a/src/core/contractors/static/codac_CtcFunction.cpp b/src/core/contractors/static/codac_CtcFunction.cpp index 5d5075f0..8e576df0 100644 --- a/src/core/contractors/static/codac_CtcFunction.cpp +++ b/src/core/contractors/static/codac_CtcFunction.cpp @@ -9,7 +9,6 @@ */ #include "codac_CtcFunction.h" -#include "ibex_CtcFwdBwd.h" using namespace std; using namespace ibex; diff --git a/src/core/contractors/static/codac_CtcFunction.h b/src/core/contractors/static/codac_CtcFunction.h index 95d964b9..1c5a9151 100644 --- a/src/core/contractors/static/codac_CtcFunction.h +++ b/src/core/contractors/static/codac_CtcFunction.h @@ -13,7 +13,7 @@ #define __CODAC_CTCFUNCTION_H__ #include -#include "ibex_Function.h" +#include "codac_Function.h" #include "ibex_CtcFwdBwd.h" #include "ibex_Domain.h" #include "codac_TubeVector.h" @@ -35,7 +35,7 @@ namespace codac * * \param f the function \f$\mathbf{f}\f$ */ - CtcFunction(const ibex::Function& f); + CtcFunction(const Function& f); /** * \brief Creates a contractor for the constraint \f$\mathbf{f}(\mathbf{x})\in[\mathbf{y}]\f$ @@ -44,7 +44,7 @@ namespace codac * \param f the function \f$\mathbf{f}\f$ * \param y the ibex::Domain object */ - CtcFunction(const ibex::Function& f, const ibex::Domain& y); + CtcFunction(const Function& f, const ibex::Domain& y); /** * \brief Creates a contractor for the constraint \f$f(\mathbf{x})\in[y]\f$ @@ -53,7 +53,7 @@ namespace codac * \param f the function \f$f\f$ * \param y the interval \f$[y]\f$ */ - CtcFunction(const ibex::Function& f, const Interval& y); + CtcFunction(const Function& f, const Interval& y); /** * \brief Creates a contractor for the constraint \f$\mathbf{f}(\mathbf{x})\in[\mathbf{y}]\f$ @@ -62,7 +62,7 @@ namespace codac * \param f the function \f$\mathbf{f}\f$ * \param y the IntervalVector \f$[\mathbf{y}]\f$ */ - CtcFunction(const ibex::Function& f, const IntervalVector& y); + CtcFunction(const Function& f, const IntervalVector& y); /** * \brief \f$\mathcal{C}\big([\mathbf{x}]\big)\f$ diff --git a/src/core/domains/tube/codac_TubeVector.h b/src/core/domains/tube/codac_TubeVector.h index 7cb18241..e2a88051 100644 --- a/src/core/domains/tube/codac_TubeVector.h +++ b/src/core/domains/tube/codac_TubeVector.h @@ -480,7 +480,7 @@ namespace codac * * \return the maximal thicknesses of this tube */ - const ibex::Vector max_diam() const; + const Vector max_diam() const; /** * \brief Returns the slices diagonals of the tube as a trajectory @@ -708,7 +708,7 @@ namespace codac * \param rad half of the inflation for each component * \return *this */ - const TubeVector& inflate(const ibex::Vector& rad); + const TubeVector& inflate(const Vector& rad); /** * \brief Inflates this tube by adding non-constant uncertainties defined in a trajectory diff --git a/src/core/functions/codac_Function.h b/src/core/functions/codac_Function.h new file mode 100644 index 00000000..835b4b07 --- /dev/null +++ b/src/core/functions/codac_Function.h @@ -0,0 +1,22 @@ +/** + * \file + * Function class + * ---------------------------------------------------------------------------- + * \date 2021 + * \author Simon Rohou + * \copyright Copyright 2021 Codac Team + * \license This program is distributed under the terms of + * the GNU Lesser General Public License (LGPL). + */ + +#ifndef __CODAC_FUNCTION_H__ +#define __CODAC_FUNCTION_H__ + +#include "ibex_Function.h" + +namespace codac +{ + using ibex::Function; +} + +#endif \ No newline at end of file diff --git a/src/core/functions/codac_TFunction.h b/src/core/functions/codac_TFunction.h index 0fc8fd41..ce4880e5 100644 --- a/src/core/functions/codac_TFunction.h +++ b/src/core/functions/codac_TFunction.h @@ -12,7 +12,7 @@ #define __CODAC_TFUNCTION_H__ #include -#include "ibex_Function.h" +#include "codac_Function.h" #include "codac_TFnc.h" #include "codac_Trajectory.h" #include "codac_TrajectoryVector.h" @@ -23,13 +23,13 @@ namespace codac class Trajectory; class TrajectoryVector; - std::string to_string(const ibex::Function& f); + std::string to_string(const Function& f); class TFunction : public TFnc { public: - TFunction(const ibex::Function& f); + TFunction(const Function& f); TFunction(const char* y); TFunction(const char* x1, const char* y); TFunction(const char* x1, const char* x2, const char* y); @@ -47,7 +47,7 @@ namespace codac const TFunction operator[](int i) const; const std::string& expr() const; - const ibex::Function& getFunction() const; + const Function& getFunction() const; const std::string arg_name(int i) const; using TFnc::eval; @@ -74,8 +74,8 @@ namespace codac void construct_from_array(int n, const char** x, const char* y); - ibex::Function *m_ibex_f = NULL; - std::string m_expr; // stored here because impossible to get this value from ibex::Function + Function *m_ibex_f = NULL; + std::string m_expr; // stored here because impossible to get this value from Function }; } diff --git a/src/core/geometry/codac_ConvexPolygon.h b/src/core/geometry/codac_ConvexPolygon.h index 1daadbdb..db34aba5 100644 --- a/src/core/geometry/codac_ConvexPolygon.h +++ b/src/core/geometry/codac_ConvexPolygon.h @@ -28,7 +28,7 @@ namespace codac ConvexPolygon(const ConvexPolygon& p); explicit ConvexPolygon(const IntervalVector& box); ConvexPolygon(const std::vector& v_thick_pts); - ConvexPolygon(const std::vector& v_floating_pts, bool convex_and_convention_order = false); + ConvexPolygon(const std::vector& v_floating_pts, bool convex_and_convention_order = false); /// @} /// \name Tests diff --git a/src/core/geometry/codac_Edge.h b/src/core/geometry/codac_Edge.h index e5722cc1..6a17e933 100644 --- a/src/core/geometry/codac_Edge.h +++ b/src/core/geometry/codac_Edge.h @@ -11,7 +11,7 @@ #ifndef __CODAC_EDGE_H__ #define __CODAC_EDGE_H__ -#include "ibex_Vector.h" +#include "codac_Vector.h" #include "codac_Interval.h" #include "codac_IntervalVector.h" #include "codac_BoolInterval.h" @@ -27,7 +27,7 @@ namespace codac /// @{ Edge(const Point& p1, const Point& p2); - Edge(const ibex::Vector& p1, const ibex::Vector& p2); + Edge(const Vector& p1, const Vector& p2); const Edge& operator=(const Edge& e); /// @} diff --git a/src/core/geometry/codac_GrahamScan.h b/src/core/geometry/codac_GrahamScan.h index a275c3b6..a606ad43 100644 --- a/src/core/geometry/codac_GrahamScan.h +++ b/src/core/geometry/codac_GrahamScan.h @@ -25,16 +25,16 @@ namespace codac public: // Prints convex hull of a set of n points. - static const std::vector convex_hull(const std::vector& v_points); + static const std::vector convex_hull(const std::vector& v_points); protected: // A utility function to find next to top in a stack - static const ibex::Vector next_to_top(const std::stack& s); + static const Vector next_to_top(const std::stack& s); // A utility function to swap two points - static void swap(ibex::Vector& p1, ibex::Vector& p2); + static void swap(Vector& p1, Vector& p2); // A utility function to return square of distance between p1 and p2 static const Interval dist(const IntervalVector& p1, const IntervalVector& p2); @@ -50,12 +50,12 @@ namespace codac { public: - PointsSorter(const ibex::Vector& p0); - bool operator()(const ibex::Vector& p1, const ibex::Vector& p2); + PointsSorter(const Vector& p0); + bool operator()(const Vector& p1, const Vector& p2); protected: - ibex::Vector m_p0 = ibex::Vector(2); + Vector m_p0 = Vector(2); }; } diff --git a/src/core/geometry/codac_Point.h b/src/core/geometry/codac_Point.h index 7f26fb6f..8872f8da 100644 --- a/src/core/geometry/codac_Point.h +++ b/src/core/geometry/codac_Point.h @@ -20,7 +20,7 @@ #endif // _MSC_VER #include -#include "ibex_Vector.h" +#include "codac_Vector.h" #include "codac_Interval.h" #include "codac_IntervalVector.h" #include "codac_BoolInterval.h" @@ -39,7 +39,7 @@ namespace codac /// @{ Point(); // undefined point - explicit Point(const ibex::Vector& p); + explicit Point(const Vector& p); explicit Point(const IntervalVector& p); Point(const Interval& x, const Interval& y); const Point& operator=(const Point& p); @@ -52,9 +52,9 @@ namespace codac const Interval& y() const; const Interval& operator[](size_t id) const; const IntervalVector& box() const; - const ibex::Vector mid() const; + const Vector mid() const; double max_diam() const; - const std::vector bounds_pts() const; + const std::vector bounds_pts() const; /// @} /// \name Tests @@ -84,10 +84,10 @@ namespace codac static const BoolInterval aligned(const Point& a, const Point& b, const Point& c); static const Point center(const std::vector v_pts); static void push(const IntervalVector& box, std::vector& v_pts); - static void push(const IntervalVector& box, std::vector& v_pts); - static std::vector to_Points(const std::vector& v_pts); + static void push(const IntervalVector& box, std::vector& v_pts); + static std::vector to_Points(const std::vector& v_pts); static std::vector remove_identical_pts(const std::vector& v_pts); - static std::vector remove_identical_pts(const std::vector& v_pts); + static std::vector remove_identical_pts(const std::vector& v_pts); /// @} diff --git a/src/core/geometry/codac_Polygon.h b/src/core/geometry/codac_Polygon.h index 6117726d..2721a515 100644 --- a/src/core/geometry/codac_Polygon.h +++ b/src/core/geometry/codac_Polygon.h @@ -12,7 +12,7 @@ #define __CODAC_POLYGON_H__ #include -#include "ibex_Vector.h" +#include "codac_Vector.h" #include "codac_IntervalVector.h" #include "codac_Edge.h" #include "codac_Point.h" @@ -28,7 +28,7 @@ namespace codac Polygon(); Polygon(const Polygon& p); - Polygon(const std::vector& v_floating_pts); + Polygon(const std::vector& v_floating_pts); /// @} /// \name Accessing values @@ -38,8 +38,8 @@ namespace codac int nb_edges() const; int nb_vertices() const; const std::vector edges() const; - const std::vector& vertices() const; - const ibex::Vector& operator[](size_t vertex_id) const; + const std::vector& vertices() const; + const Vector& operator[](size_t vertex_id) const; const IntervalVector box() const; const Point center() const; const Interval area() const; @@ -65,7 +65,7 @@ namespace codac protected: - std::vector m_v_floating_pts; + std::vector m_v_floating_pts; }; } diff --git a/src/core/paving/codac_ConnectedSubset.h b/src/core/paving/codac_ConnectedSubset.h index 23a7e90b..9e723c15 100644 --- a/src/core/paving/codac_ConnectedSubset.h +++ b/src/core/paving/codac_ConnectedSubset.h @@ -235,7 +235,7 @@ namespace codac * \param precision of the bisected method used in case of ambiguity on the already existing paving structure * \return `true` if the Jacobian is non-singular */ - bool non_singular_jacobian(const std::function& f, float precision); + bool non_singular_jacobian(const std::function& Jf, float precision); /// @} diff --git a/src/core/paving/codac_SIVIAPaving.h b/src/core/paving/codac_SIVIAPaving.h index f5951a1d..fe56b4a1 100644 --- a/src/core/paving/codac_SIVIAPaving.h +++ b/src/core/paving/codac_SIVIAPaving.h @@ -13,7 +13,7 @@ #define __CODAC_SIVIAPAVING_H__ #include "codac_Paving.h" -#include "ibex_Function.h" +#include "codac_Function.h" #include "codac_IntervalVector.h" namespace codac @@ -43,7 +43,7 @@ namespace codac * \param y box \f$[\mathbf{y}]\f$ * \param precision precision \f$\epsilon\f$ of the SIVIA approximation */ - void compute(const ibex::Function& f, const IntervalVector& y, float precision); + void compute(const Function& f, const IntervalVector& y, float precision); /// @} }; diff --git a/src/core/serialize/codac_serialize_trajectories.cpp b/src/core/serialize/codac_serialize_trajectories.cpp index af1d4c47..6745d83b 100644 --- a/src/core/serialize/codac_serialize_trajectories.cpp +++ b/src/core/serialize/codac_serialize_trajectories.cpp @@ -8,7 +8,7 @@ * the GNU Lesser General Public License (LGPL). */ -#include "ibex_Vector.h" +#include "codac_Vector.h" #include "codac_Exception.h" #include "codac_serialize_trajectories.h" diff --git a/src/core/tools/codac_Eigen.cpp b/src/core/tools/codac_Eigen.cpp index 9cc0fa83..54dc187b 100644 --- a/src/core/tools/codac_Eigen.cpp +++ b/src/core/tools/codac_Eigen.cpp @@ -2,7 +2,7 @@ namespace codac { -Eigen::MatrixXd EigenHelpers::i2e(const ibex::Matrix &x) { +Eigen::MatrixXd EigenHelpers::i2e(const Matrix &x) { Eigen::MatrixXd m(x.nb_rows(), x.nb_cols()); for (int i = 0; i < x.nb_rows(); ++i) { for (int j = 0; j < x.nb_cols(); ++j) { @@ -12,7 +12,7 @@ Eigen::MatrixXd EigenHelpers::i2e(const ibex::Matrix &x) { return m; } -Eigen::MatrixXd EigenHelpers::i2e(const ibex::Vector &x) { +Eigen::MatrixXd EigenHelpers::i2e(const Vector &x) { Eigen::MatrixXd m(x.size(), 1); for (int i = 0; i < x.size(); ++i) { m(i, 1) = x[i]; @@ -20,8 +20,8 @@ Eigen::MatrixXd EigenHelpers::i2e(const ibex::Vector &x) { return m; } -ibex::Matrix EigenHelpers::e2i(const Eigen::MatrixXd &x) { - ibex::Matrix m(x.rows(), x.cols()); +Matrix EigenHelpers::e2i(const Eigen::MatrixXd &x) { + Matrix m(x.rows(), x.cols()); for (unsigned int i = 0; i < x.rows(); ++i) { for (unsigned int j = 0; j < x.cols(); ++j) { m[i][j] = x(i, j); diff --git a/src/core/tools/codac_Eigen.h b/src/core/tools/codac_Eigen.h index 2b85cfb8..0da4e09c 100644 --- a/src/core/tools/codac_Eigen.h +++ b/src/core/tools/codac_Eigen.h @@ -1,19 +1,19 @@ #ifndef CODAC_LIB_CODAC_EIGEN_H #define CODAC_LIB_CODAC_EIGEN_H -#include -#include +#include +#include #include namespace codac { class EigenHelpers { public: - static Eigen::MatrixXd i2e(const ibex::Matrix &x); + static Eigen::MatrixXd i2e(const Matrix &x); - static Eigen::MatrixXd i2e(const ibex::Vector &x); + static Eigen::MatrixXd i2e(const Vector &x); - static ibex::Matrix e2i(const Eigen::MatrixXd &x); + static Matrix e2i(const Eigen::MatrixXd &x); }; } diff --git a/src/core/variables/real/codac_Matrix.h b/src/core/variables/real/codac_Matrix.h new file mode 100644 index 00000000..e66c3ec0 --- /dev/null +++ b/src/core/variables/real/codac_Matrix.h @@ -0,0 +1,22 @@ +/** + * \file + * Matrix class + * ---------------------------------------------------------------------------- + * \date 2021 + * \author Simon Rohou + * \copyright Copyright 2021 Codac Team + * \license This program is distributed under the terms of + * the GNU Lesser General Public License (LGPL). + */ + +#ifndef __CODAC_MATRIX_H__ +#define __CODAC_MATRIX_H__ + +#include "ibex_Matrix.h" + +namespace codac +{ + using ibex::Matrix; +} + +#endif \ No newline at end of file diff --git a/src/core/variables/real/codac_Vector.h b/src/core/variables/real/codac_Vector.h new file mode 100644 index 00000000..0043e503 --- /dev/null +++ b/src/core/variables/real/codac_Vector.h @@ -0,0 +1,22 @@ +/** + * \file + * Vector class + * ---------------------------------------------------------------------------- + * \date 2021 + * \author Simon Rohou + * \copyright Copyright 2021 Codac Team + * \license This program is distributed under the terms of + * the GNU Lesser General Public License (LGPL). + */ + +#ifndef __CODAC_VECTOR_H__ +#define __CODAC_VECTOR_H__ + +#include "ibex_Vector.h" + +namespace codac +{ + using ibex::Vector; +} + +#endif \ No newline at end of file diff --git a/src/core/variables/trajectory/codac_TrajectoryVector.h b/src/core/variables/trajectory/codac_TrajectoryVector.h index b1dab051..b958e365 100644 --- a/src/core/variables/trajectory/codac_TrajectoryVector.h +++ b/src/core/variables/trajectory/codac_TrajectoryVector.h @@ -14,7 +14,7 @@ #include #include -#include "ibex_Vector.h" +#include "codac_Vector.h" #include "codac_Interval.h" #include "codac_TFunction.h" #include "codac_Trajectory.h" @@ -70,7 +70,7 @@ namespace codac * * \param m_map_values map defining the trajectory: \f$\mathbf{x}(t)=\mathbf{y}\f$ */ - explicit TrajectoryVector(const std::map& m_map_values); + explicit TrajectoryVector(const std::map& m_map_values); /** * \brief Creates a n-dimensional trajectory \f$\mathbf{x}(\cdot)\f$ from a vector of maps of scalar values @@ -193,7 +193,7 @@ namespace codac * \param t the temporal key (double, must belong to the trajectory's tdomain) * \return real vector value \f$\mathbf{x}(t)\f$ */ - const ibex::Vector operator()(double t) const; + const Vector operator()(double t) const; /** * \brief Returns the interval evaluation of this trajectory over \f$[t]\f$ @@ -208,14 +208,14 @@ namespace codac * * \return real value \f$\mathbf{x}(t_0)\f$ */ - const ibex::Vector first_value() const; + const Vector first_value() const; /** * \brief Returns the value \f$\mathbf{x}(t_f)\f$ * * \return real value \f$\mathbf{x}(t_f)\f$ */ - const ibex::Vector last_value() const; + const Vector last_value() const; /// @} /// \name Tests @@ -255,7 +255,7 @@ namespace codac * \param y local vector value of the trajectory * \param t the temporal key (double, must belong to the trajectory's tdomain) */ - void set(const ibex::Vector& y, double t); + void set(const Vector& y, double t); /** * \brief Truncates the tdomain of \f$\mathbf{x}(\cdot)\f$ @@ -335,7 +335,7 @@ namespace codac * \param c the constant of integration * \return a new TrajectoryVector object with the same temporal keys */ - const TrajectoryVector primitive(const ibex::Vector& c) const; + const TrajectoryVector primitive(const Vector& c) const; /** * \brief Computes an approximative primitive of \f$\mathbf{x}(\cdot)\f$ @@ -345,7 +345,7 @@ namespace codac * \param timestep sampling value \f$\delta\f$ for the temporal discretization (double) * \return a new TrajectoryVector object with the specified time discretization */ - const TrajectoryVector primitive(const ibex::Vector& c, double timestep) const; + const TrajectoryVector primitive(const Vector& c, double timestep) const; /** * \brief Differentiates this trajectory vector @@ -384,7 +384,7 @@ namespace codac * \param x Vector * \return (*this)+=x */ - const TrajectoryVector& operator+=(const ibex::Vector& x); + const TrajectoryVector& operator+=(const Vector& x); /** * \brief Operates += @@ -416,7 +416,7 @@ namespace codac * \param x Vector * \return (*this)-=x */ - const TrajectoryVector& operator-=(const ibex::Vector& x); + const TrajectoryVector& operator-=(const Vector& x); /** * \brief Operates -= diff --git a/src/core/variables/trajectory/codac_TrajectoryVector_operators.cpp b/src/core/variables/trajectory/codac_TrajectoryVector_operators.cpp index bb73c051..711e0193 100644 --- a/src/core/variables/trajectory/codac_TrajectoryVector_operators.cpp +++ b/src/core/variables/trajectory/codac_TrajectoryVector_operators.cpp @@ -8,7 +8,7 @@ * the GNU Lesser General Public License (LGPL). */ -#include "ibex_Vector.h" +#include "codac_Vector.h" #include "codac_Trajectory.h" #include "codac_TrajectoryVector.h" diff --git a/src/robotics/contractors/codac_CtcConstell.h b/src/robotics/contractors/codac_CtcConstell.h index 096a565d..bdcaf09a 100644 --- a/src/robotics/contractors/codac_CtcConstell.h +++ b/src/robotics/contractors/codac_CtcConstell.h @@ -13,7 +13,7 @@ #include #include -#include "ibex_Ctc.h" +#include "codac_Ctc.h" #include namespace codac @@ -22,7 +22,7 @@ namespace codac * \brief CtcConstell class. * */ - class CtcConstell : public ibex::Ctc + class CtcConstell : public Ctc { public: diff --git a/src/robotics/data/codac_DataLoader.h b/src/robotics/data/codac_DataLoader.h index 23e62f14..3eb28f9f 100644 --- a/src/robotics/data/codac_DataLoader.h +++ b/src/robotics/data/codac_DataLoader.h @@ -39,13 +39,13 @@ namespace codac static std::vector generate_landmarks(const IntervalVector& map_box, int nb_landmarks = 100); static std::vector generate_landmarks_boxes(const IntervalVector& map_box, int nb_landmarks = 100); static std::vector generate_observations( - const ibex::Vector& x, + const Vector& x, const std::vector& map, bool random = true, const Interval& visi_range = Interval::POS_REALS, const Interval& visi_angle = Interval::ALL_REALS); static std::vector generate_observations( - const ibex::Vector& x, + const Vector& x, const std::vector& map, bool random = true, const Interval& visi_range = Interval::POS_REALS, @@ -67,7 +67,7 @@ namespace codac const Interval& visi_angle = Interval(-M_PI/4.,M_PI/4.), const Interval& tdomain = Interval::ALL_REALS); static std::vector generate_static_observations( - const ibex::Vector& x, + const Vector& x, const std::vector& map, bool random = true, const Interval& visi_range = Interval::POS_REALS, diff --git a/src/robotics/graphics/codac_VIBesFigMap.h b/src/robotics/graphics/codac_VIBesFigMap.h index 5985a54c..547d0d3c 100644 --- a/src/robotics/graphics/codac_VIBesFigMap.h +++ b/src/robotics/graphics/codac_VIBesFigMap.h @@ -248,7 +248,7 @@ namespace codac * \param pose vector (x,y[,heading]) describing robot's pose (2d or 3d) * \param size optional robot size (-1 = size of main vehicle by default) */ - void draw_vehicle(const ibex::Vector& pose, float size = -1); + void draw_vehicle(const Vector& pose, float size = -1); /** * \brief Draws a vehicle with a given pose @@ -257,7 +257,7 @@ namespace codac * \param params VIBes parameters related to the vehicle (for groups) * \param size optional robot size (-1 = size of main vehicle by default) */ - void draw_vehicle(const ibex::Vector& pose, const vibes::Params& params, float size = -1); + void draw_vehicle(const Vector& pose, const vibes::Params& params, float size = -1); /** * \brief Draws a vehicle on top of its trajectory @@ -314,7 +314,7 @@ namespace codac * \param width the real width of the squared beacon * \param color optional color of the beacon */ - void add_beacon(const ibex::Vector& beacon, double width, const std::string& color = DEFAULT_BEACON_COLOR); + void add_beacon(const Vector& beacon, double width, const std::string& color = DEFAULT_BEACON_COLOR); /** * \brief Adds a set of Beacon objects to the map @@ -354,7 +354,7 @@ namespace codac * \param width the width of the squared beacons * \param color optional color of the beacons */ - void add_landmarks(const std::vector& v_m, double width, const std::string& color = DEFAULT_BEACON_COLOR); + void add_landmarks(const std::vector& v_m, double width, const std::string& color = DEFAULT_BEACON_COLOR); /** * \brief Adds a range-and-bearing uncertain observation to the map, @@ -367,7 +367,7 @@ namespace codac * \param pose the related 3d Vector object representing the pose (x,y,heading) * \param color optional color of the observation */ - void add_observation(const IntervalVector& obs, const ibex::Vector& pose, const std::string& color = DEFAULT_OBS_COLOR); + void add_observation(const IntervalVector& obs, const Vector& pose, const std::string& color = DEFAULT_OBS_COLOR); /** * \brief Adds a set of range-and-bearing uncertain observations to the map, @@ -380,7 +380,7 @@ namespace codac * \param pose the related 3d Vector object representing the pose (x,y,heading) * \param color optional color of the observation */ - void add_observations(const std::vector& v_obs, const ibex::Vector& pose, const std::string& color = DEFAULT_OBS_COLOR); + void add_observations(const std::vector& v_obs, const Vector& pose, const std::string& color = DEFAULT_OBS_COLOR); /** * \brief Adds a range-and-bearing uncertain observation to the map, @@ -482,7 +482,7 @@ namespace codac * \param color color of the observation * \param params VIBes parameters related to the observation */ - void draw_observation(const IntervalVector& obs, const ibex::Vector& pose, const std::string& color, const vibes::Params& params); + void draw_observation(const IntervalVector& obs, const Vector& pose, const std::string& color, const vibes::Params& params); /** * \brief Draws a range-and-bearing uncertain observation on the map diff --git a/src/robotics/objects/codac_Beacon.h b/src/robotics/objects/codac_Beacon.h index 75255c65..f13ecb14 100644 --- a/src/robotics/objects/codac_Beacon.h +++ b/src/robotics/objects/codac_Beacon.h @@ -11,6 +11,7 @@ #ifndef __CODAC_BEACON_H__ #define __CODAC_BEACON_H__ +#include "codac_Vector.h" #include "codac_IntervalVector.h" namespace codac @@ -20,17 +21,17 @@ namespace codac public: Beacon(double x = 0., double y = 0., double z = 0.); - Beacon(const ibex::Vector& pos); + Beacon(const Vector& pos); Beacon(const IntervalVector& pos_box); double x() const; double y() const; double z() const; - const ibex::Vector& pos() const; + const Vector& pos() const; const IntervalVector& pos_box() const; protected: - ibex::Vector m_pos = ibex::Vector(3, 0.); + Vector m_pos = Vector(3, 0.); IntervalVector m_pos_box = IntervalVector(3); }; } diff --git a/tests/catch/catch_interval.hpp b/tests/catch/catch_interval.hpp index 88af18eb..8f5a2a62 100644 --- a/tests/catch/catch_interval.hpp +++ b/tests/catch/catch_interval.hpp @@ -20,6 +20,7 @@ #define __CODAC_CATCH_H__ #include "catch.hpp" +#include "codac_Vector.h" #include "codac_Interval.h" #include "codac_IntervalVector.h" #include "codac_Point.h" @@ -260,12 +261,12 @@ namespace Catch class ApproxVector { public: - explicit ApproxVector(ibex::Vector value, double epsilon = 100.*DEFAULT_EPSILON) : + explicit ApproxVector(codac::Vector value, double epsilon = 100.*DEFAULT_EPSILON) : m_epsilon(epsilon), m_value(value) {} - friend bool operator ==(ibex::Vector lhs, ApproxVector const& rhs) + friend bool operator ==(codac::Vector lhs, ApproxVector const& rhs) { double e = rhs.m_epsilon; @@ -279,17 +280,17 @@ namespace Catch return true; } - friend bool operator ==(ApproxVector const& lhs, ibex::Vector rhs) + friend bool operator ==(ApproxVector const& lhs, codac::Vector rhs) { return operator ==(rhs, lhs); } - friend bool operator !=(ibex::Vector lhs, ApproxVector const& rhs) + friend bool operator !=(codac::Vector lhs, ApproxVector const& rhs) { return !operator ==(lhs, rhs); } - friend bool operator !=(ApproxVector const& lhs, ibex::Vector rhs) + friend bool operator !=(ApproxVector const& lhs, codac::Vector rhs) { return !operator ==(rhs, lhs); } @@ -303,7 +304,7 @@ namespace Catch private: double m_epsilon; - ibex::Vector m_value = ibex::Vector(1); + codac::Vector m_value = codac::Vector(1); }; class ApproxIntvPair