Skip to content

Commit

Permalink
[core] Remove return codes and throw exceptions instead. (#713)
Browse files Browse the repository at this point in the history
* [core] Remove return codes and throw exceptions instead.
* [misc] Update C++ dependencies to latest releases.
  • Loading branch information
duburcqa committed Feb 11, 2024
1 parent c904739 commit 81f3dee
Show file tree
Hide file tree
Showing 95 changed files with 3,764 additions and 5,611 deletions.
5 changes: 3 additions & 2 deletions .github/workflows/macos.yml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,8 @@ jobs:
strategy:
matrix:
OS: ['macos-14'] # 'macos-13': Intel (x86), 'macos-14': Apple Silicon (arm64)
OS: ['macos-13'] # 'macos-13': Intel (x86), 'macos-14': Apple Silicon (arm64)
# meshcat video recorder 'playwright' is not working on 'macos-14' runners.
PYTHON_VERSION: ['3.10', '3.11', '3.12'] # `setup-python` does not support Python<3.10 on Apple Silicon
BUILD_TYPE: ['Release']
include:
Expand All @@ -25,7 +26,7 @@ jobs:
- OS: 'macos-13'
PYTHON_VERSION: '3.9'
BUILD_TYPE: 'Release'
- OS: 'macos-14'
- OS: 'macos-13'
PYTHON_VERSION: '3.11'
BUILD_TYPE: 'Debug'

Expand Down
8 changes: 4 additions & 4 deletions build_tools/build_install_deps_unix.sh
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ if [ ! -d "${RootDir}/eigenpy" ]; then
fi
cd "${RootDir}/eigenpy"
git reset --hard
git fetch origin "v3.1.4" && git checkout --force FETCH_HEAD || true
git fetch origin "v3.3.0" && git checkout --force FETCH_HEAD || true
git submodule --quiet foreach --recursive git reset --quiet --hard
git submodule --quiet update --init --recursive --depth 1 --jobs 8
git apply --reject --whitespace=fix "${RootDir}/build_tools/patch_deps_unix/eigenpy.patch"
Expand Down Expand Up @@ -155,7 +155,7 @@ if [ ! -d "${RootDir}/cppad" ]; then
fi
cd "${RootDir}/cppad"
git reset --hard
git fetch origin "20230000.0" && git checkout --force FETCH_HEAD || true
git fetch origin "20240000.2" && git checkout --force FETCH_HEAD || true

### Checkout CppADCodeGen
if [ ! -d "${RootDir}/cppadcodegen" ]; then
Expand All @@ -180,7 +180,7 @@ if [ ! -d "${RootDir}/hpp-fcl" ]; then
fi
cd "${RootDir}/hpp-fcl"
git reset --hard
git fetch origin "v2.4.0" && git checkout --force FETCH_HEAD || true
git fetch origin "v2.4.1" && git checkout --force FETCH_HEAD || true
git submodule --quiet foreach --recursive git reset --quiet --hard
git submodule --quiet update --init --recursive --depth 1 --jobs 8
git apply --reject --whitespace=fix "${RootDir}/build_tools/patch_deps_unix/hppfcl.patch"
Expand All @@ -194,7 +194,7 @@ if [ ! -d "${RootDir}/pinocchio" ]; then
fi
cd "${RootDir}/pinocchio"
git reset --hard
git fetch origin "v2.6.21" && git checkout --force FETCH_HEAD || true
git fetch origin "v2.7.0" && git checkout --force FETCH_HEAD || true
git submodule --quiet foreach --recursive git reset --quiet --hard
git submodule --quiet update --init --recursive --depth 1 --jobs 8
git apply --reject --whitespace=fix "${RootDir}/build_tools/patch_deps_unix/pinocchio.patch"
Expand Down
8 changes: 4 additions & 4 deletions build_tools/build_install_deps_windows.ps1
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ if (-not (Test-Path -PathType Container "$RootDir/eigenpy")) {
}
Push-Location -Path "$RootDir/eigenpy"
git reset --hard
git fetch origin "v3.1.4"
git fetch origin "v3.3.0"
git checkout --force FETCH_HEAD
git submodule --quiet foreach --recursive git reset --quiet --hard
git submodule --quiet update --init --recursive --depth 1 --jobs 8
Expand Down Expand Up @@ -164,7 +164,7 @@ if (-not (Test-Path -PathType Container "$RootDir/cppad")) {
}
Push-Location -Path "$RootDir/cppad"
git reset --hard
git fetch origin "20230000.0"
git fetch origin "20240000.2"
git checkout --force FETCH_HEAD
Pop-Location

Expand Down Expand Up @@ -195,7 +195,7 @@ if (-not (Test-Path -PathType Container "$RootDir/hpp-fcl")) {
}
Push-Location -Path "$RootDir/hpp-fcl"
git reset --hard
git fetch origin "v2.4.0"
git fetch origin "v2.4.1"
git checkout --force FETCH_HEAD
git submodule --quiet foreach --recursive git reset --quiet --hard
git submodule --quiet update --init --recursive --depth 1 --jobs 8
Expand All @@ -214,7 +214,7 @@ if (-not (Test-Path -PathType Container "$RootDir/pinocchio")) {
}
Push-Location -Path "$RootDir/pinocchio"
git reset --hard
git fetch origin "v2.6.21"
git fetch origin "v2.7.0"
git checkout --force FETCH_HEAD
git submodule --quiet foreach --recursive git reset --quiet --hard
git submodule --quiet update --init --recursive --depth 1 --jobs 8
Expand Down
15 changes: 14 additions & 1 deletion build_tools/cmake/base.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,18 @@ if(CMAKE_VERSION VERSION_GREATER_EQUAL 3.27.0)
cmake_policy(SET CMP0144 NEW)
endif()

# Forces GCC/Clang compilers to enable color diagnostics.
# CMake versions 3.24 and below do not support this option, so we have
# to invoke the color diagnostics flags manually.
set(CMAKE_COLOR_DIAGNOSTICS ON)
if(CMAKE_VERSION VERSION_LESS "3.24.0")
if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
add_compile_options(-fdiagnostics-color=always)
elseif(CMAKE_CXX_COMPILER_ID STREQUAL "Clang")
add_compile_options(-fcolor-diagnostics)
endif()
endif()

# Check if network is available before compiling external projects
if(WIN32)
find_program(HAS_PING "ping")
Expand Down Expand Up @@ -54,7 +66,8 @@ else()
-Wno-unknown-warning -Wno-undefined-var-template \
-Wno-long-long -Wno-error=maybe-uninitialized \
-Wno-error=uninitialized -Wno-error=deprecated \
-Wno-error=array-bounds -Wno-error=redundant-move")
-Wno-error=array-bounds -Wno-error=redundant-move \
-Wno-error=suggest-attribute=noreturn")
endif()

# Shared libraries need PIC
Expand Down
4 changes: 2 additions & 2 deletions build_tools/easy_install_deps_ubuntu.sh
Original file line number Diff line number Diff line change
Expand Up @@ -81,8 +81,8 @@ fi
# Note that `apt-get` is used instead of `apt` because it supports wildcard in package names
apt-mark unhold "robotpkg-py3*-eigenpy" "robotpkg-py3*-hpp-fcl" "robotpkg-py3*-pinocchio"
apt-get install -y --allow-downgrades --allow-unauthenticated \
robotpkg-urdfdom-headers=1.0.4 robotpkg-hpp-fcl=2.4.0 robotpkg-pinocchio=2.6.21 \
robotpkg-py3*-eigenpy=3.1.4 robotpkg-py3*-hpp-fcl=2.4.0 robotpkg-py3*-pinocchio=2.6.21
robotpkg-urdfdom-headers=1.0.4 robotpkg-hpp-fcl=2.4.1 robotpkg-pinocchio=2.7.0 \
robotpkg-py3*-eigenpy=3.3.0 robotpkg-py3*-hpp-fcl=2.4.1 robotpkg-py3*-pinocchio=2.7.0
apt-mark hold "robotpkg-py3*-eigenpy" "robotpkg-py3*-hpp-fcl" "robotpkg-py3*-pinocchio"

# Add openrobots libraries to python packages search path
Expand Down
8 changes: 4 additions & 4 deletions build_tools/patch_deps_unix/hppfcl.patch
Original file line number Diff line number Diff line change
Expand Up @@ -15,17 +15,17 @@ diff --git a/CMakeLists.txt b/CMakeLists.txt
SET_BOOST_DEFAULT_OPTIONS()
EXPORT_BOOST_DEFAULT_OPTIONS()
-IF(WIN32)
- ADD_PROJECT_DEPENDENCY(Boost REQUIRED COMPONENTS chrono thread date_time serialization)
- ADD_PROJECT_DEPENDENCY(Boost REQUIRED COMPONENTS chrono thread date_time serialization filesystem)
-ELSE(WIN32)
- ADD_PROJECT_DEPENDENCY(Boost REQUIRED chrono serialization)
- ADD_PROJECT_DEPENDENCY(Boost REQUIRED chrono serialization filesystem)
-ENDIF(WIN32)
if(BUILD_PYTHON_INTERFACE)
find_package(Boost REQUIRED COMPONENTS system)
endif(BUILD_PYTHON_INTERFACE)
+IF(WIN32)
+ ADD_PROJECT_DEPENDENCY(Boost REQUIRED COMPONENTS chrono thread date_time serialization)
+ ADD_PROJECT_DEPENDENCY(Boost REQUIRED COMPONENTS chrono thread date_time serialization filesystem)
+ELSE(WIN32)
+ ADD_PROJECT_DEPENDENCY(Boost REQUIRED chrono serialization)
+ ADD_PROJECT_DEPENDENCY(Boost REQUIRED chrono serialization filesystem)
+ENDIF(WIN32)

if(Boost_VERSION_STRING VERSION_LESS 1.81)
Expand Down
2 changes: 1 addition & 1 deletion build_tools/patch_deps_windows/hppfcl.patch
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ diff --git a/CMakeLists.txt b/CMakeLists.txt
if(BUILD_PYTHON_INTERFACE)
FIND_PACKAGE(eigenpy 2.7.10 REQUIRED)
@@ -121,34 +122,24 @@
ADD_PROJECT_DEPENDENCY(Boost REQUIRED chrono serialization)
ADD_PROJECT_DEPENDENCY(Boost REQUIRED chrono serialization filesystem)
ENDIF(WIN32)
if(BUILD_PYTHON_INTERFACE)
+ ADD_PROJECT_DEPENDENCY(Boost REQUIRED system)
Expand Down
13 changes: 0 additions & 13 deletions build_tools/patch_deps_windows/pinocchio.patch
Original file line number Diff line number Diff line change
Expand Up @@ -83,16 +83,3 @@ diff --git a/cmake/boost.cmake b/cmake/boost.cmake
set(Boost_NO_BOOST_CMAKE ON)
endif("${Boost_SHORT_VERSION}" VERSION_GREATER "1.70"
OR "${Boost_SHORT_VERSION}" VERSION_EQUAL "1.70")
diff --git a/bindings/python/utils/conversions.cpp b/bindings/python/utils/conversions.cpp
index 87800d2b..c73707e5 100644
--- a/bindings/python/utils/conversions.cpp
+++ b/bindings/python/utils/conversions.cpp
@@ -37,7 +37,7 @@ namespace pinocchio
template <typename TupleOrList>
SE3 XYZQUATToSE3_bp(const TupleOrList& v)
{
- ssize_t size = bp::len(v);
+ bp::ssize_t size = bp::len(v);
if(size != 7)
{
throw std::invalid_argument(
21 changes: 10 additions & 11 deletions core/examples/double_pendulum/double_pendulum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,8 @@ int main(int /* argc */, char * /* argv */[])
controller->initialize(robot);

// Instantiate and configuration the engine
auto engine = std::make_shared<Engine>();
GenericConfig simuOptions = engine->getOptions();
Engine engine{};
GenericConfig simuOptions = engine.getOptions();
GenericConfig & telemetryOptions = boost::get<GenericConfig>(simuOptions.at("telemetry"));
boost::get<bool>(telemetryOptions.at("isPersistent")) = true;
boost::get<bool>(telemetryOptions.at("enableConfiguration")) = true;
Expand Down Expand Up @@ -118,8 +118,8 @@ int main(int /* argc */, char * /* argv */[])
boost::get<double>(contactsOptions.at("friction")) = 5.0;
boost::get<double>(contactsOptions.at("transitionEps")) = 0.001;
boost::get<double>(contactsOptions.at("transitionVelocity")) = 0.01;
engine->setOptions(simuOptions);
engine->initialize(robot, controller, callback);
engine.setOptions(simuOptions);
engine.initialize(robot, controller, callback);
std::cout << "Initialization: " << timer.toc<std::milli>() << "ms" << std::endl;

// =====================================================================
Expand All @@ -134,20 +134,19 @@ int main(int /* argc */, char * /* argv */[])

// Run simulation
timer.tic();
engine->simulate(tf, q0, v0);
engine.simulate(tf, q0, v0);
std::cout << "Simulation: " << timer.toc<std::milli>() << "ms" << std::endl;

// Write the log file
std::vector<std::string> fieldnames;
std::shared_ptr<const LogData> logData;
engine->getLog(logData);
std::cout << logData->times.size() << " log points" << std::endl;
std::cout << engine->getStepperState().iter << " internal integration steps" << std::endl;
std::shared_ptr<const LogData> logDataPtr = engine.getLog();
std::cout << logDataPtr->times.size() << " log points" << std::endl;
std::cout << engine.getStepperState().iter << " internal integration steps" << std::endl;
timer.tic();
engine->writeLog((outputDirPath / "log.data").string(), "binary");
engine.writeLog((outputDirPath / "log.data").string(), "binary");
std::cout << "Write log binary: " << timer.toc<std::milli>() << "ms" << std::endl;
timer.tic();
engine->writeLog((outputDirPath / "log.hdf5").string(), "hdf5");
engine.writeLog((outputDirPath / "log.hdf5").string(), "hdf5");
std::cout << "Write log HDF5: " << timer.toc<std::milli>() << "ms" << std::endl;

return 0;
Expand Down
17 changes: 8 additions & 9 deletions core/examples/external_project/double_pendulum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -81,8 +81,8 @@ int main(int argc, char * argv[])
controller->initialize(robot);

// Instantiate the engine
auto engine = std::make_shared<Engine>();
engine->initialize(robot, controller, callback);
Engine engine{};
engine.initialize(robot, controller, callback);
std::cout << "Initialization: " << timer.toc<std::milli>() << "ms" << std::endl;

// =====================================================================
Expand All @@ -97,19 +97,18 @@ int main(int argc, char * argv[])

// Run simulation
timer.tic();
engine->simulate(tf, q0, v0);
engine.simulate(tf, q0, v0);
std::cout << "Simulation: " << timer.toc<std::milli>() << "ms" << std::endl;

// Write the log file
std::vector<std::string> fieldnames;
std::shared_ptr<const LogData> logData;
engine->getLog(logData);
std::cout << logData->times.size() << " log points" << std::endl;
std::cout << engine->getStepperState().iter << " internal integration steps" << std::endl;
std::shared_ptr<const LogData> logDataPtr = engine.getLog();
std::cout << logDataPtr->times.size() << " log points" << std::endl;
std::cout << engine.getStepperState().iter << " internal integration steps" << std::endl;
timer.tic();
engine->writeLog((outputDirPath / "log.data").string(), "binary");
engine.writeLog((outputDirPath / "log.data").string(), "binary");
std::cout << "Write log binary: " << timer.toc<std::milli>() << "ms" << std::endl;
engine->writeLog((outputDirPath / "log.hdf5").string(), "hdf5");
engine.writeLog((outputDirPath / "log.hdf5").string(), "hdf5");
std::cout << "Write log HDF5: " << timer.toc<std::milli>() << "ms" << std::endl;

return 0;
Expand Down
14 changes: 7 additions & 7 deletions core/include/jiminy/core/constraints/abstract_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,17 +29,17 @@ namespace jiminy
///
/// \remark This method is not intended to be called manually. The Robot to which the
/// constraint is added is taking care of it when its own `reset` method is called.
virtual hresult_t reset(const Eigen::VectorXd & q, const Eigen::VectorXd & v) = 0;
virtual void reset(const Eigen::VectorXd & q, const Eigen::VectorXd & v) = 0;

void enable();
void disable();
bool getIsEnabled() const;

hresult_t setBaumgartePositionGain(double kp);
void setBaumgartePositionGain(double kp);
double getBaumgartePositionGain() const;
hresult_t setBaumgarteVelocityGain(double kd);
void setBaumgarteVelocityGain(double kd);
double getBaumgarteVelocityGain() const;
hresult_t setBaumgarteFreq(double freq);
void setBaumgarteFreq(double freq);
/// \brief Natural frequency of critically damping position/velocity error correction.
double getBaumgarteFreq() const;

Expand All @@ -50,8 +50,8 @@ namespace jiminy
///
/// \param[in] q Current joint position.
/// \param[in] v Current joint velocity.
virtual hresult_t computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) = 0;
virtual void computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) = 0;

virtual const std::string & getType() const = 0;

Expand All @@ -70,7 +70,7 @@ namespace jiminy
/// \param[in] model Model on which to apply the constraint.
///
/// \return Error code: attach may fail, including if the constraint is already attached.
hresult_t attach(std::weak_ptr<const Model> model);
void attach(std::weak_ptr<const Model> model);

/// \brief Detach the constraint from its model.
void detach();
Expand Down
9 changes: 4 additions & 5 deletions core/include/jiminy/core/constraints/distance_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,14 +27,13 @@ namespace jiminy
const std::array<std::string, 2> & getFramesNames() const noexcept;
const std::array<pinocchio::FrameIndex, 2> & getFrameIndices() const noexcept;

hresult_t setReferenceDistance(double distanceRef);
void setReferenceDistance(double distanceRef);
double getReferenceDistance() const noexcept;

virtual hresult_t reset(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;
virtual void reset(const Eigen::VectorXd & q, const Eigen::VectorXd & v) override final;

virtual hresult_t computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;
virtual void computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;

private:
/// \brief Names of the frames on which the constraint operates.
Expand Down
7 changes: 3 additions & 4 deletions core/include/jiminy/core/constraints/frame_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,10 @@ namespace jiminy
void setNormal(const Eigen::Vector3d & normal) noexcept;
const Eigen::Matrix3d & getLocalFrame() const noexcept;

virtual hresult_t reset(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;
virtual void reset(const Eigen::VectorXd & q, const Eigen::VectorXd & v) override final;

virtual hresult_t computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;
virtual void computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;

private:
/// \brief Name of the frame on which the constraint operates.
Expand Down
7 changes: 3 additions & 4 deletions core/include/jiminy/core/constraints/joint_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,10 @@ namespace jiminy
void setRotationDir(bool isReversed) noexcept;
bool getRotationDir() noexcept;

virtual hresult_t reset(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;
virtual void reset(const Eigen::VectorXd & q, const Eigen::VectorXd & v) override final;

virtual hresult_t computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;
virtual void computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;

private:
/// \brief Name of the joint on which the constraint operates.
Expand Down
8 changes: 4 additions & 4 deletions core/include/jiminy/core/constraints/sphere_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,11 @@ namespace jiminy
void setReferenceTransform(const pinocchio::SE3 & transformRef) noexcept;
const pinocchio::SE3 & getReferenceTransform() const noexcept;

virtual hresult_t reset(const Eigen::VectorXd & /* q */,
const Eigen::VectorXd & /* v */) override final;
virtual void reset(const Eigen::VectorXd & /* q */,
const Eigen::VectorXd & /* v */) override final;

virtual hresult_t computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;
virtual void computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;

private:
/// \brief Name of the frame on which the constraint operates.
Expand Down
8 changes: 4 additions & 4 deletions core/include/jiminy/core/constraints/wheel_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,11 @@ namespace jiminy
void setReferenceTransform(const pinocchio::SE3 & transformRef) noexcept;
const pinocchio::SE3 & getReferenceTransform() const noexcept;

virtual hresult_t reset(const Eigen::VectorXd & /* q */,
const Eigen::VectorXd & /* v */) override final;
virtual void reset(const Eigen::VectorXd & /* q */,
const Eigen::VectorXd & /* v */) override final;

virtual hresult_t computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;
virtual void computeJacobianAndDrift(const Eigen::VectorXd & q,
const Eigen::VectorXd & v) override final;

private:
/// \brief Name of the frame on which the constraint operates.
Expand Down
Loading

0 comments on commit 81f3dee

Please sign in to comment.