Skip to content

Commit

Permalink
Jiminy release 1.8.5 (#777)
Browse files Browse the repository at this point in the history
* [core] Full support of serialization of 'Robot'. (#770) (#775) 
* [core] Do NOT use 'enable_shared_from_this' if not strictly necessary. (#775) 
* [core] Rename macro 'PRINT_WARNING' in 'JIMINY_WARNING' to avoid conflicts. (#775) 
* [python/simulator] 'plot' now support multi-robot simulations. (#770)
* [gym/common] Speedup 'PDController' env pipeline block. (#770)
* [gym/common] Speedup 'StackedJiminyEnv' wrapper. (#770)
* [gym/common] More generic 'FilterObservation', 'StackedJiminyEnv' wrappers.  (#770) (#776)
* [gym/common] Improve 'render_mode' support.
* [gym/zoo] Cleanup and speedup toy model environments. (#770)
* [gym/rllib] Fix multi-GPU support using custom PPO (#774)
* [gym/rllib] Fix 'train' method typing and documentation. (#775) 
* [misc] Fix partially broken 'mypy' static type checking for 'jiminy_py' module. (#770)
* [misc] Add RL tutorial notebook.
  • Loading branch information
duburcqa authored Apr 28, 2024
1 parent 60f60ec commit 43a3f56
Show file tree
Hide file tree
Showing 69 changed files with 3,990 additions and 1,041 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/linux.yml
Original file line number Diff line number Diff line change
Expand Up @@ -155,8 +155,8 @@ jobs:
# Anyway, the stubs generated for eigenpy, hppfcl and pinocchio they are incomplete and
# even partially wrong, so it is better to ignore them for now.
# See: https://github.com/python/mypy/issues/14848.
cd "${RootDir}/python/jiminy_py/"
mypy --config-file="${RootDir}/.mypy.ini" -p src
cd "${RootDir}/python/jiminy_py/src"
mypy --config-file="${RootDir}/.mypy.ini" -p jiminy_py
for name in "common" "envs" "toolbox" "rllib"; do
cd "${RootDir}/python/gym_jiminy/$name"
mypy --config-file="${RootDir}/.mypy.ini" -p gym_jiminy
Expand Down
8 changes: 4 additions & 4 deletions .github/workflows/ubuntu.yml
Original file line number Diff line number Diff line change
Expand Up @@ -99,8 +99,8 @@ jobs:
-DCMAKE_SHARED_LINKER_FLAGS="${{ matrix.LINKER_FLAGS }}" \
-DCMAKE_C_COMPILER="${CMAKE_C_COMPILER}" -DCMAKE_CXX_COMPILER="${CMAKE_CXX_COMPILER}" \
-DCMAKE_PREFIX_PATH="/opt/openrobots/" -DCMAKE_INSTALL_PREFIX="${InstallDir}" \
-DCMAKE_INTERPROCEDURAL_OPTIMIZATION=ON -DBoost_NO_SYSTEM_PATHS=OFF \
-DPYTHON_EXECUTABLE="${PYTHON_EXECUTABLE}" \
-DCMAKE_INTERPROCEDURAL_OPTIMIZATION=${{ (matrix.BUILD_TYPE == 'Debug' && 'OFF') || 'ON' }} \
-DBoost_NO_SYSTEM_PATHS=OFF -DPYTHON_EXECUTABLE="${PYTHON_EXECUTABLE}" \
-DBUILD_TESTING=ON -DBUILD_EXAMPLES=ON -DBUILD_PYTHON_INTERFACE=ON \
-DCMAKE_BUILD_TYPE="${{ matrix.BUILD_TYPE }}"
if [[ "${{ matrix.GENERATOR }}" == 'Ninja' ]] ; then
Expand All @@ -127,8 +127,8 @@ jobs:
-DCMAKE_SHARED_LINKER_FLAGS="${{ matrix.LINKER_FLAGS }}" \
-DCMAKE_C_COMPILER="${CMAKE_C_COMPILER}" -DCMAKE_CXX_COMPILER="${CMAKE_CXX_COMPILER}" \
-DCMAKE_PREFIX_PATH="/opt/openrobots/" -DCMAKE_INSTALL_PREFIX="${InstallDir}" \
-DCMAKE_INTERPROCEDURAL_OPTIMIZATION=ON -DPYTHON_EXECUTABLE="${PYTHON_EXECUTABLE}" \
-DCMAKE_BUILD_TYPE="${{ matrix.BUILD_TYPE }}"
-DCMAKE_INTERPROCEDURAL_OPTIMIZATION=${{ (matrix.BUILD_TYPE == 'Debug' && 'OFF') || 'ON' }} \
-DPYTHON_EXECUTABLE="${PYTHON_EXECUTABLE}" -DCMAKE_BUILD_TYPE="${{ matrix.BUILD_TYPE }}"
if [[ "${{ matrix.GENERATOR }}" == 'Ninja' ]] ; then
ninja install
else
Expand Down
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
cmake_minimum_required(VERSION 3.12.4)

# Set the build version (specify a tweak version to indicated post-release if needed)
set(BUILD_VERSION 1.8.4)
set(BUILD_VERSION 1.8.5)

# MSVC runtime library flags are defined by 'CMAKE_MSVC_RUNTIME_LIBRARY'
if(CMAKE_VERSION VERSION_GREATER_EQUAL 3.15.7)
Expand Down
21 changes: 13 additions & 8 deletions build_tools/cmake/base.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@ if(CMAKE_VERSION VERSION_LESS "3.24.0")
endif()

# Check if network is available before compiling external projects
if(WIN32)
set(BUILD_OFFLINE 0)
else()
set(BUILD_OFFLINE 0)
find_program(PING "ping")
if(NOT WIN32 AND PING)
unset(BUILD_OFFLINE)
unset(BUILD_OFFLINE CACHE)
execute_process(COMMAND bash -c
Expand Down Expand Up @@ -49,12 +49,17 @@ else()
-Wsequence-point -Wdeprecated -Wconversion \
-Wdelete-non-virtual-dtor -Wno-missing-braces \
-Wno-sign-conversion -Wno-non-virtual-dtor \
-Wno-unknown-pragmas -Wno-unknown-warning-option \
-Wno-unknown-warning -Wno-undefined-var-template \
-Wno-long-long -Wno-error=maybe-uninitialized \
-Wno-unknown-pragmas -Wno-long-long \
-Wno-error=uninitialized -Wno-error=deprecated \
-Wno-error=array-bounds -Wno-error=redundant-move \
-Wno-error=suggest-attribute=noreturn")
-Wno-error=array-bounds -Wno-error=redundant-move")
if (CMAKE_CXX_COMPILER_ID MATCHES "Clang")
set(WARN_FULL "${WARN_FULL} \
-Wno-undefined-var-template -Wno-unknown-warning-option")
elseif (CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
set(WARN_FULL "${WARN_FULL} \
-Wno-error=maybe-uninitialized \
-Wno-error=suggest-attribute=noreturn")
endif()
endif()

# Shared libraries need PIC
Expand Down
6 changes: 1 addition & 5 deletions core/include/jiminy/core/constraints/abstract_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@ namespace jiminy
class Model;

/// \brief Generic interface for kinematic constraints.
class JIMINY_DLLAPI AbstractConstraintBase :
public std::enable_shared_from_this<AbstractConstraintBase>
class JIMINY_DLLAPI AbstractConstraintBase
{
// See AbstractSensor for comment on this.
friend Model;
Expand Down Expand Up @@ -102,9 +101,6 @@ namespace jiminy
class JIMINY_TEMPLATE_DLLAPI AbstractConstraintTpl : public AbstractConstraintBase
{
public:
auto shared_from_this() { return shared_from(this); }
auto shared_from_this() const { return shared_from(this); }

const std::string & getType() const { return type_; }

public:
Expand Down
4 changes: 1 addition & 3 deletions core/include/jiminy/core/constraints/distance_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,12 @@ namespace jiminy
public:
JIMINY_DISABLE_COPY(DistanceConstraint)

auto shared_from_this() { return shared_from(this); }

public:
explicit DistanceConstraint(const std::string & firstFrameName,
const std::string & secondFrameName) noexcept;
virtual ~DistanceConstraint() = default;

const std::array<std::string, 2> & getFramesNames() const noexcept;
const std::array<std::string, 2> & getFrameNames() const noexcept;
const std::array<pinocchio::FrameIndex, 2> & getFrameIndices() const noexcept;

void setReferenceDistance(double distanceRef);
Expand Down
2 changes: 0 additions & 2 deletions core/include/jiminy/core/constraints/frame_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,6 @@ namespace jiminy
public:
JIMINY_DISABLE_COPY(FrameConstraint)

auto shared_from_this() { return shared_from(this); }

public:
/// \param[in] frameName Name of the frame on which the constraint is to be
/// applied.
Expand Down
4 changes: 1 addition & 3 deletions core/include/jiminy/core/constraints/joint_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,6 @@ namespace jiminy
public:
JIMINY_DISABLE_COPY(JointConstraint)

auto shared_from_this() { return shared_from(this); }

public:
/// \param[in] jointName Name of the joint.
explicit JointConstraint(const std::string & jointName) noexcept;
Expand All @@ -38,7 +36,7 @@ namespace jiminy
const Eigen::VectorXd & getReferenceConfiguration() const noexcept;

void setRotationDir(bool isReversed) noexcept;
bool getRotationDir() noexcept;
bool getRotationDir() const noexcept;

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

Expand Down
5 changes: 3 additions & 2 deletions core/include/jiminy/core/constraints/sphere_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,6 @@ namespace jiminy
public:
JIMINY_DISABLE_COPY(SphereConstraint)

auto shared_from_this() { return shared_from(this); }

public:
/// \param[in] frameName Name of the frame representing the center of the sphere.
/// \param[in] sphereRadius Radius of the sphere (in m).
Expand All @@ -42,6 +40,9 @@ namespace jiminy
const std::string & getFrameName() const noexcept;
pinocchio::FrameIndex getFrameIndex() const noexcept;

double getRadius() const noexcept;
const Eigen::Vector3d & getNormal() const noexcept;

void setReferenceTransform(const pinocchio::SE3 & transformRef) noexcept;
const pinocchio::SE3 & getReferenceTransform() const noexcept;

Expand Down
6 changes: 4 additions & 2 deletions core/include/jiminy/core/constraints/wheel_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,6 @@ namespace jiminy
public:
JIMINY_DISABLE_COPY(WheelConstraint)

auto shared_from_this() { return shared_from(this); }

public:
/// \param[in] frameName Name of the frame representing the center of the wheel.
/// \param[in] wheelRadius Radius of the wheel (in m).
Expand All @@ -41,6 +39,10 @@ namespace jiminy
const Eigen::Vector3d & wheelAxis) noexcept;
virtual ~WheelConstraint() = default;

double getRadius() const noexcept;
const Eigen::Vector3d & getNormal() const noexcept;
const Eigen::Vector3d & getWheelAxis() const noexcept;

const std::string & getFrameName() const noexcept;
pinocchio::FrameIndex getFrameIndex() const noexcept;

Expand Down
15 changes: 8 additions & 7 deletions core/include/jiminy/core/hardware/abstract_motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ namespace jiminy
std::size_t num_;
};

class JIMINY_DLLAPI AbstractMotorBase : public std::enable_shared_from_this<AbstractMotorBase>
class JIMINY_DLLAPI AbstractMotorBase
{
/* AKA AbstractSensorBase */
friend Robot;
Expand Down Expand Up @@ -120,6 +120,9 @@ namespace jiminy
/// \param[in] motorOptions Dictionary with the parameters used for any motor.
void setOptionsAll(const GenericConfig & motorOptions);

/// \brief Whether the motor has been attached to a robot.
bool getIsAttached() const;

/// \brief Whether the motor has been initialized.
bool getIsInitialized() const;

Expand Down Expand Up @@ -192,16 +195,14 @@ namespace jiminy
/// \brief Reference to the last data buffer corresponding to the true effort of the motor.
double & data();

bool isAttached() const;

private:
/// \brief Attach the sensor to a robot
///
/// \details This method must be called before initializing the sensor.
void attach(std::weak_ptr<const Robot> robot,
std::function<void(
AbstractMotorBase & /*motor*/, bool /*hasChanged*/)> notifyRobot,
MotorSharedStorage * sharedStorage);
void attach(
std::weak_ptr<const Robot> robot,
std::function<void(AbstractMotorBase & /*motor*/, bool /*hasChanged*/)> notifyRobot,
MotorSharedStorage * sharedStorage);

/// \brief Detach the sensor from the robot.
void detach();
Expand Down
12 changes: 4 additions & 8 deletions core/include/jiminy/core/hardware/abstract_sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,7 @@ namespace jiminy
/// \brief Generic interface for any sensor.
///
/// \details Any sensor must inherit from this base class and implement its virtual methods.
class JIMINY_DLLAPI AbstractSensorBase :
public std::enable_shared_from_this<AbstractSensorBase>
class JIMINY_DLLAPI AbstractSensorBase
{
/* Using friend to avoid double delegation, which would make public the attach, whereas
only robot is able to call it.
Expand Down Expand Up @@ -182,15 +181,15 @@ namespace jiminy
/// higher dimensional tensor.
virtual Eigen::Ref<const Eigen::VectorXd> get() const = 0;

/// \brief Whether the sensor has been attached to a robot.
bool getIsAttached() const;

/// \brief Whether the sensor has been initialized.
///
/// \remark Note that a sensor can be considered initialized even if its telemetry is not
/// properly configured. If not, it must be done before being ready to use.
bool getIsInitialized() const;

/// \brief Whether the sensor has been attached to a robot.
bool getIsAttached() const;

/// \brief Whether the telemetry of the controller has been initialized.
bool getIsTelemetryConfigured() const;

Expand Down Expand Up @@ -323,9 +322,6 @@ namespace jiminy
using AbstractSensorBase::AbstractSensorBase;
virtual ~AbstractSensorTpl();

auto shared_from_this() { return shared_from(this); }
auto shared_from_this() const { return shared_from(this); }

void resetAll(uint32_t seed) override final;
void updateTelemetryAll() override final;

Expand Down
3 changes: 0 additions & 3 deletions core/include/jiminy/core/hardware/basic_motors.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,6 @@ namespace jiminy
explicit SimpleMotor(const std::string & name) noexcept;
virtual ~SimpleMotor() = default;

auto shared_from_this() { return shared_from(this); }
auto shared_from_this() const { return shared_from(this); }

void initialize(const std::string & jointName);

void setOptions(const GenericConfig & motorOptions) override;
Expand Down
10 changes: 0 additions & 10 deletions core/include/jiminy/core/hardware/basic_sensors.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,6 @@ namespace jiminy
public:
using AbstractSensorTpl<ImuSensor>::AbstractSensorTpl;

auto shared_from_this() { return shared_from(this); }

void initialize(const std::string & frameName);

void setOptions(const GenericConfig & sensorOptions) override;
Expand Down Expand Up @@ -64,8 +62,6 @@ namespace jiminy
public:
using AbstractSensorTpl<ContactSensor>::AbstractSensorTpl;

auto shared_from_this() { return shared_from(this); }

void initialize(const std::string & frameName);

void setOptions(const GenericConfig & sensorOptions) override;
Expand Down Expand Up @@ -102,8 +98,6 @@ namespace jiminy
public:
using AbstractSensorTpl<ForceSensor>::AbstractSensorTpl;

auto shared_from_this() { return shared_from(this); }

void initialize(const std::string & frameName);

void setOptions(const GenericConfig & sensorOptions) override;
Expand Down Expand Up @@ -143,8 +137,6 @@ namespace jiminy
public:
using AbstractSensorTpl<EncoderSensor>::AbstractSensorTpl;

auto shared_from_this() { return shared_from(this); }

void initialize(const std::string & jointName);

void setOptions(const GenericConfig & sensorOptions) override;
Expand Down Expand Up @@ -182,8 +174,6 @@ namespace jiminy
public:
using AbstractSensorTpl<EffortSensor>::AbstractSensorTpl;

auto shared_from_this() { return shared_from(this); }

void initialize(const std::string & motorName);

void setOptions(const GenericConfig & sensorOptions) override;
Expand Down
74 changes: 74 additions & 0 deletions core/include/jiminy/core/io/serialization.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,80 @@
#ifndef JIMINY_SERIALIZATION_H
#define JIMINY_SERIALIZATION_H

#include <optional> // `std::optional`
#include <string> // `std::string`
#include <vector> // `std::vector`
#include <memory> // `std::shared_ptr`

#include "jiminy/core/fwd.h"


// Forward declarations
namespace pinocchio
{
struct GeometryObject;
struct GeometryModel;
}

namespace jiminy
{
class Model;
class Robot;

class stateful_binary_iarchive;
class stateful_binary_oarchive;
}

/* Jiminy-specific API for saving and loading data to binary format.
Internally, it leverages `boost::serialization`, but unlike the classic interface `serialize`,
it can be specified to pass option arguments, which allows for providing opt-in storage
optimizations and recovery information when loading partially corrupted data. */
namespace jiminy
{
template<typename T>
std::string saveToBinary(const T & obj);

template<typename T>
void loadFromBinary(T & obj, const std::string & data);

std::string saveToBinary(const std::shared_ptr<jiminy::Robot> & robot,
bool isPersistent = true);

void loadFromBinary(std::shared_ptr<jiminy::Robot> & robot,
const std::string & data,
const std::optional<std::string> & meshPathDir = std::nullopt,
const std::vector<std::string> & meshPackageDirs = {});
}

/* Partial specialization of `boost::serialization` API to enable serialization of complex classes.
Unlike `loadFromBinary`, `saveToBinary`, this API does not expose mechanics to customize its
internal, so the most conservation assumptions are made, eventually impeding performance. */
namespace boost::serialization
{
// *************************************** pinocchio *************************************** //

template<class Archive>
void load_construct_data(
Archive & ar, pinocchio::GeometryObject * geomPtr, const unsigned int version);

template<class Archive>
void serialize(Archive & ar, pinocchio::GeometryObject & geom, const unsigned int version);

template<class Archive>
void serialize(Archive & ar, pinocchio::GeometryModel & model, const unsigned int version);

// ***************************************** jiminy **************************************** //

template<class Archive>
void serialize(Archive & ar, jiminy::Model & model, const unsigned int version);

template<class Archive>
void load_construct_data(Archive & ar, jiminy::Robot * robotPtr, const unsigned int version);

template<class Archive>
void serialize(Archive & ar, jiminy::Robot & robot, const unsigned int version);
}

#include "jiminy/core/io/serialization.hxx"

#endif // JIMINY_SERIALIZATION_H
Loading

0 comments on commit 43a3f56

Please sign in to comment.