Jiminy, fast and portable Python/C++ simulator of poly-articulated systems with OpenAI Gym interface for reinforcement learning.

Overview

Jiminy is a fast and portable cross-platform open-source simulator for poly-articulated systems. It was built with two ideas in mind:

  • provide a fast yet physically accurate simulator for robotics research.

Jiminy is built around Pinocchio, an open-source fast and efficient kinematics and dynamics library. Jiminy thus uses minimal coordinates and Lagrangian dynamics to simulate an articulated system: this makes Jiminy as close as numerically possible to an analytical solution, without the risk of joint violation.

  • build an efficient and flexible platform for machine learning in robotics.

Beside a strong focus on performance to answer machine learning's need for running computationally demanding distributed simulations, Jiminy offers convenience tools for learning via a dedicated module Gym-Jiminy. It is fully compliant with gym standard API and provides an highly customizable wrapper to interface any robotics system with state-of-the-art learning frameworks.

Key features

General

  • Simulation of multi-body systems using minimal coordinates and Lagrangian dynamics.
  • Comprehensive API for computing dynamic quantities and their derivatives, exposing and extending Pinocchio.
  • C++ core with full python bindings, providing frontend API parity between both languages.
  • Designed with machine learning in mind, with seemless wrapping of robots as OpenAI Gym environments using one-liners. Jiminy provides both the physical engine and the robot model (including sensors) required for learning.
  • Easy to install: pip is all that is needed to get you started !
  • Dedicated integration in Google Colab, Jupyter Lab, and VSCode working out-of-the-box - including interactive 3D viewer based on Meshcat. This facilitates working on remote headless environnement such as machine learning clusters.
  • Cross-platform offscreen rendering capability, without requiring X-server, based on Panda3d.
  • Rich simulation log output, easily customizable for recording, introspection and debugging. The simulation log is made available in RAM directly for fast access, and can be exported in raw binary, CSV or HDF5 format.
  • Support Linux, Mac and Windows platforms.

Physics

  • Provide both classical phenomenological force-level spring-damper contact model and constraint solver based on maximum energy dissipation principle.
  • Support contact and collision with the ground, using either a fixed set of contact points or collision meshes and primitives.
  • Able to simulate multiple articulated systems simultaneously, interacting with each other, to support use cases such as multi-agent reinforcement learning or swarm robotics.
  • Support of compliant joints with force-based spring-damper dynamics, to model joint elasticity, a common phenomenon particularly in legged robotics.
  • Simulate both continuous or discrete-time controller, with possibly different controller and sensor update frequencies.

A more complete list of features, development status, and changelog are available on the wiki.

The documentation is available on Github.io, or locally in docs/html/index.html if built from source.

Gym Jiminy

Gym Jiminy is an interface between Jiminy simulator and reinforcement learning frameworks. It is fully compliant with now standard Open AI Gym API. Additionally, it offers a generic and easily configurable learning environment for learning locomotion tasks, with minimal intervention from the user, who usually only needs to provide the robot's URDF file. Furthermore, Gym Jiminy enables easy modification of many aspects of the simulation to provide richer exploration and ensure robust learning. This ranges from external perturbation forces to sensor noise and bias, including randomization of masses and inertias, ground friction model or even gravity itself. Note that learning can easily be done on any high-level dynamics features, or restricted to mock sensor data for end-to-end learning.

Gym is cross-platform and compatible with most Reinforcement Learning frameworks implementing standard algorithms. For instance, Stable Baselines 3, RL Coach, Tianshou, or Rllib. RL Coach leverages the open-source Machine Learning framework Tensorflow as backend, Stable Baselines 3 and Tianshou use its counterpart Pytorch, and Rllib supports both. A few learning examples relying on those packages are also provided.

Pre-configured environments for some well-known toys models and reference robotics platforms are provided: cartpole, acrobot, pendulum, Ant, ANYmal, and Cassie, and Atlas.

Demo

Getting started

Jiminy and Gym Jiminy support Linux, Mac and Windows, and is compatible with Python3.6+. Pre-compiled binaries are distributed on PyPi for Python 3.6/3.7/3.8/3.9. They can be installed using pip:

# For installing Jiminy
python -m pip install jiminy_py

# For installing Gym Jiminy
python -m pip install gym_jiminy[all]

Detailed installation instructions, including building from source, are available here.

Comments
  • Modelling flexible link robots using virtual link/joint method

    Modelling flexible link robots using virtual link/joint method

    Hi! I want to model a flexible link robot by truncating the link into several virtual links connected by means of passive virtual joints with certain stiffness and damping (see the figure below, it explains the concept for single link robot). I have a URDF file that describes approximated model, but it doesn't contain joint stiffness and damping. I want to implement a simulator for training and RL agent. Is it possible to it using jiminy? Do you have any examples of flexible robots? What is the best place to start implementing flexible link robot simulator?

    Thank you in advance!

    flexible_link d

    opened by shamilmamedov 44
  • Adding position constraint

    Adding position constraint

    Hello,

    I am trying to simulate a robot sitting on a chair by constraining a point in the robot to have its position fixed. Can I do this in Jiminy (C++) ?

    Thanks!

    opened by vcparedesc 14
  • Failures in engine while trying to run Environment

    Failures in engine while trying to run Environment

    Hi, I'm trying to train an agent to run the Anymal Environment in jupyter notebook with python 3.8.10.

    I'm getting this error in the notebook:

    RuntimeError                              Traceback (most recent call last)
    <ipython-input-58-238be5bf9bbb> in <module>
    
    ---> 18     env.step(action)
    
    ~/.local/lib/python3.8/site-packages/gym_jiminy/common/envs/env_generic.py in step(self, action)
        745 
        746         # Perform a single simulation step
    --> 747         self.simulator.step(self.step_dt)
        748 
        749         # Update shared buffers
    
    ~/.local/lib/python3.8/site-packages/jiminy_py/simulator.py in step(self, step_dt)
        404         return_code = self.engine.step(step_dt)
        405         if return_code != jiminy.hresult_t.SUCCESS:
    --> 406             raise RuntimeError("Failed to perform the simulation step.")
        407 
        408     def simulate(self,
    
    RuntimeError: Failed to perform the simulation step.
    

    And I'm getting this error printed to the terminal:

    In /__w/jiminy/jiminy/core/src/engine/EngineMultiRobot.cc:2242: In jiminy::EngineMultiRobot::step:
    error: Too many successive iteration failures. Probably something is going wrong with the physics. Aborting integration.
    

    Simple code to reproduce (you may have to run a few times)

    from gym_jiminy.envs import ANYmalJiminyEnv
    
    env = ANYmalJiminyEnv()
    
    env.reset()
    
    for i in range(1000):
        action = env.action_space.sample()
        env.step(action)
      
    
    print('do I get here?')
    
    
    opened by Le5tes 10
  • Meshcat in COLAB

    Meshcat in COLAB

    Dear @duburcqa,

    Following the discussion https://github.com/RobotLocomotion/drakae/issues/12645, did you manage to get a colab session with MeshCat? If so, could you provide some pointers? We (with @nim65s) would be interested to watch and take inspiration from the solution.

    opened by jcarpent 10
  • [jiminy_py] Add option for plotter to compare several logfiles.

    [jiminy_py] Add option for plotter to compare several logfiles.

    One of the main purpose I use jiminy for is to compare two simulations of the same system, with different parameters. In that context, I get two log files, with the same content (in terms of logged fields) and length.

    This PR adds the capacity for jiminy_plotter to compare two or more logs, by plotting them on the same graph:

    jiminy_plotter logfile.data regex -c the_logs_I_want_to_compare_to.data

    Feature preview:

    simu_jiminy_standstill_DTF_JointLQR data

    opened by matthieuvigne 10
  • Segmentation fault when trying to use pinocchio data

    Segmentation fault when trying to use pinocchio data

    Hello, I am using Jiminy tag version 1.6.17. I was trying to get the orientation and position of a particular link using a procedure I was using in tag version 1.6.1 however, I am getting segmentation faults. This is a minimal modification of the double pendulum example that reproduces my problem:

    void computeCommand(float64_t        const & t,
                        vectorN_t        const & q,
                        vectorN_t        const & v,
                        sensorsDataMap_t const & sensorsData,
                        vectorN_t              & command)
    {
        // No controller: energy should be preserved
       auto linkId = robot->pncModel_.getFrameId("PendulumArm");    
    }
    

    I made sure to declare "robot" as a global variable (auto robot = std::make_shared();)

    Whenever I remove the getFrameId line in computeCommand the code doesn't have any problems running, but adding the line causes the sefgaults. I am using the pip installation method for building the example.

    Victor

    bug 
    opened by vcparedesc 9
  • [python] Add generic plotting tool for jiminy logs.

    [python] Add generic plotting tool for jiminy logs.

    To make jiminy even nicer to use, this PR proposes a simple python tool, jiminy_plot, to plot the content of a logfile rapidly using matplotlib. Below is an example of rendering (actual data is meaningless):

    jiminy_plot  /tmp/example_sagittal.data H*.c*Pos*Body:H*.c*Vel*Body H*.energy
    

    example

    opened by matthieuvigne 9
  • Isolating pip build for Pinocchio

    Isolating pip build for Pinocchio

    Dear @duburcqa,

    I was wondering how does it cost to isolate the pip build for Pinocchio from your current setup? I think it might be useful to do it, in order to let external users rely on Pinocchio using pip.

    Thanks in advance for your help,

    Justin

    opened by jcarpent 8
  • Accessing pinocchio model to obtain frameId

    Accessing pinocchio model to obtain frameId

    Hello!

    I am using the pip method to build my project. Building the same project using jiminy from source would work, but now whenever I try to access the pinocchio model I get a segmentation fault. I am attaching a slightly modified version of the example pip_extension/double_pendulum.cc

    Whenever I uncomment line 38: //auto Frame_id = robot->pncModel_.getFrameId("PendulumArm");

    I get the segmentation fault. Am I using an outdated way to get the FrameId?

    Thanks!

    pip_extension.zip

    opened by vcparedesc 6
  • Missing licenses in copy/pasted files

    Missing licenses in copy/pasted files

    Hi @duburcqa,

    I really appreciate seeing Pinocchio's code to be used in external projects.

    It should be nice to keep the copyright holders of the files when lines of code have been copy-pasted from original projects. For instance, https://github.com/Wandercraft/jiminy/blob/master/python/jiminy_py/src/jiminy_py/meshcat/meshcat_visualizer.py, even if it contains some modifications. I don't think this is the only where it occurs but as a maintener of Pinocchio, I would really appreciate to see the original credits of our work.

    In addition, I see you add some features to https://github.com/Wandercraft/jiminy/blob/master/python/jiminy_py/src/jiminy_py/meshcat/meshcat_visualizer.py which can benefit to everybody. I do think you can contribute to the whole community by improving the original version here https://github.com/stack-of-tasks/pinocchio/blob/master/bindings/python/pinocchio/visualize/meshcat_visualizer.py, in the same way we are trying to help you when you encounter issues or bugs.

    Best regards,

    Justin, on the behalf of the Pinocchio's team.

    opened by jcarpent 5
  • Plotter compare

    Plotter compare

    This is a fixup of https://github.com/Wandercraft/jiminy/pull/93 : you forced push to my branch and thus removed the last commit.

    There was code ducplication left in jiminy_py between log.py and plotter.py - but only log.py is meant to be used.

    opened by matthieuvigne 5
  • [python] Get rid of `use_theoretical_model`.

    [python] Get rid of `use_theoretical_model`.

    We should get rid of use_theoretical_model everywhere to make everything more simple. The user would be responsible for converting the state for flexible to rigid or the other way around if necessary.

    opened by duburcqa 1
  • [misc] Bad docstring formatting for Boost::Python bindings.

    [misc] Bad docstring formatting for Boost::Python bindings.

    image

    I suppose the text documents an overload to the function, without being sure.

    Also, is the [ ] nesting to indicate optionality correct ? This one indicates that load_visual_meshes being present is acceptable only if has_freeflyer is present too

    opened by Arpafaucon 2
  • [core] Get rid of confusing `system` hierarchy.

    [core] Get rid of confusing `system` hierarchy.

    Currently, the sensor and controller update periods are set at engine level, while it should be specific to every robots. It would be natural to move the controller as an attribute Robot, and request the user to the setController method (currently part of EngineMultiRobot) to set it on-the-fly.

    This way, the notion of "system" can be removed altogether and replaced by "robot". The engine would still be responsible for calling the controller and its internal dynamics itself, but it is already the case for any physical quantity anyway.

    To avoid any conflict or confusion, getName method of Model should be removed, in favor of manually accessing name attribute of pinocchio_model. The robots themselves as no name anymore apart from the ones the engine is giving to them to distinguish between them. This mechanism is different from the sensors and motors and maybe should be refactor. It seems more rationale to identity them from the name their owner is giving them since they are basically all identical.

    In the same vein, registered forces should be named. Everything should return lists ordered by motors, sensors or rotor instead of a mix of unordered dicts and list as it is currently the case.

    core P0 
    opened by duburcqa 1
  • [core] Add backlash.

    [core] Add backlash.

    Bashlash can be implemented in the exact same way as flexible joints by a virtual joint with co-located with the true one and with the same DoFs. The "flexible" name should be generalized to distinguish the actual model from the theoretical one. For instance, just true versus theoretical. Getters (basically any utility) for the flexible model should be renamed accordingly.

    new feature physics core P1 
    opened by duburcqa 0
  • [python] Rationalize Python dependencies

    [python] Rationalize Python dependencies

    Remove dependency to h5py, trimesh, scipy, and tree:

    • tree: parse of variable names structure for variable registration. It could even be moved to C++, or boost::python bindings.
    • h5py: read hdf5 log files. It could be implemented in boost::python bindings.
    • trimesh: convert convex in bounding boxes. hppfcl is already capable of doing so.
    • scipy: spline interpolation of 1D sequences.
    enhancement python P1 
    opened by duburcqa 0
Releases(1.7.14)
  • 1.7.14(Oct 29, 2022)

    This release fixes many bugs that has been introduced along the way. Notably, the discontinuity of the integration state and IMU measurements have been fixed, as well as the contact dynamics.

    Improvements

    • [core] Move Baumgarte Stabilization freq from constraint to contact to avoid affecting user-specified constraints.
    • [core] Distance constraint reference now reset to current but can be updated.
    • [core/python] More pythonic bindings for EngineMultiRobot. (#559)
    • [core|python] Unify log reading/writing.
    • [python/viewer] Add method to show/hide floor programmatically.

    Patches and bug fixes

    • [python/robot] More robust hardware config file parsing.
    • [core] Fix sensor not properly initialized before calling reset at least once. (#550)
    • [core] Fix segfault at start for multi-robot simulation.
    • [core] Fix sensor not properly initialized before calling reset at least once.
    • [core] Fix Viscoelastic coupling force computation. (#553)
    • [core] Fix expose registered force profiles and impulses. (#557)
    • [core] Fix bugs in creation of flexible model.
    • [core] Fix integrate SE3 buggy in place.
    • [core] Fix continuity of the quaternion of IMU sensors.
    • [core] Fix constraints relying on wrong acceleration (classical not spatial).
    • [core] Fix sphere and wheel constraints.
    • [core/python] Fix 'forceCoupling_t::systemIdx1' expose typo.
    • [python/robot] Fix exception creating robot with non-existing urdf.
    • [python/simulator] Fix default plot 'block' argument.
    • [python/simulator] Fix native python exception handling at start.
    • [python/log] Fix creating robot from log on windows.
    • [python/viewer] Fix handling of non-existing Jupyter server in notebook.
    • [python/viewer] Fix exception when no collision bodies are specified.
    • [gym/envs] Fix ANYmal env. (#561)
    • [misc] Fix broken easy install dependencies.
    • [misc] Fix optional dependencies issues.

    Miscellaneous

    • [core/python] Do not register converters if already existing.
    • [core|python] Rename log processing helpers.
    • [misc] Add more python example scripts.
    • [misc] Relax numpy version requirement.
    • [misc] Cmake config file now properly export dependencies.
    • [misc] Fix cmake config file error when 'find_package' is called twice.
    Source code(tar.gz)
    Source code(zip)
  • 1.7.13(Jun 17, 2022)

    Adding flexibility at fixed frame is now fully supported and the integration in notebooks have been greatly improved. The interactive viewer is now working much better, notably on Mybinder or Kaggle. As a fallback, a static video mode for notebooks has been added and is used preferably on google colab that is still working unreliably. Besides, meshes with texture are now loading properly in Meshcat.

    https://user-images.githubusercontent.com/17752950/174389897-9911370b-0e08-4c73-885c-b58d86142672.mp4

    New features

    • [python/viewer] Load collada mesh with texture in Meshcat.
    • [python/viewer] Add video replay in notebook as a fallback.

    Improvements

    • [core] Add rest length to directional coupling force.
    • [python/viewer] Add option to resize video recordings.
    • [python/viewer] Improve support of interactive mode in notebook.
    • [core] Adding deformation point at frame no longer requires a valid URDF file.

    Patches and bug fixes

    • [core] Backup URDF as string right when initializing the robot for persistence.
    • [core] Force persistent log mode if no urdf associated with robot.
    • [core] Check if acceleration is still valid after starting the simulation.
    • [core] Fix serialization issue when importing pinocchio before jiminy.
    • [core] Fix segfault when initializing motor with non-existing joint.
    • [core] Fix wrong geometry parent joint and placement after adding flexibility.
    • [core] Fix adding flexibility at frames at successive fixed frames.
    • [core|python] Fix access and view of theoretical model.
    • [python/viewer] Fix capsule shading in Meshcat.
    • [python/viewer] Fix exception handling when closing viewer during replay.
    • [python/viewer] Fix iopub msg rate limit in notebook.
    • [misc] Fix video recording with panda3d for cpu-only machine.

    Miscellaneous

    • [python/viewer] Add watchdog mechanism to handle loss connections in notebook.
    • [misc] Update all dependencies.
    • [misc] 'torch' dependency is optional for gym_jiminy_toolbox.
    • [misc] Add support of Python 3.10 except for gym_jiminy_rllib.
    • [misc] Drop support of Python 3.6 and 3.7 on MacOS.
    Source code(tar.gz)
    Source code(zip)
  • 1.7.12(May 30, 2022)

    This release fixes a bunch of bugs mainly introduced by the previous one and extend the serialization to geometry models to support convex shapes.

    Improvements

    • [core] Add serialization of convex geometries.
    • [python/viewer] Enhance lighting for panda3d.

    Patches and bug fixes

    • [core|python] Fix read/write of log files for HDF5 and CSV formats.
    • [python/log] Fix deserialization of pinocchio models in log files with HDF5 format.
    • [python/viewer] Fix flipped overlay for panda3d.
    • [python/viewer] Fix update color and improve except handling for legend.
    • [python/viewer] Fix loading of Convex geometries.
    • [python/viewer] Fix shadows on floor if available with EGL driver for panda3d.

    Miscellaneous

    • [misc] Fix wheel deploy for gym jiminy.
    • [misc] Fix gym jiminy inter-dependencies.
    Source code(tar.gz)
    Source code(zip)
  • 1.7.11(May 27, 2022)

    It is now possible to dump the whole robot (including visual and collision meshes) in log files. These standalone log files can be replayed on any system without requiring any extra file. It is convenient for sharing simulation results and safe long-term backups.

    New features

    • [core] Enable serialization of geometry models optionally.

    Improvements

    • [core] Refactor telemetry to support binary object dump as constant.
    • [core] Simulation time unit is now fixed to 1e-10.
    • [core] Add option to force loading visual meshes.
    • [python/simulator] 'plot' is blocking by default if not interactive.
    • [python/log] Build robot from logged models.
    • [python/viewer] Fallback to loading geometry if path not available.
    • [python/viewer] Add option to render markers on background.

    Patches and bug fixes

    • [core] Fix definition of time unit in log files.
    • [core] Fix reading of binary log files.
    • [core] Fix writing log with no data available.
    • [python/plot] Fig figure sometimes rendered blank.
    • [python/plot] Fix figure offscreen rendering.
    • [misc] Fix python importlib usage.
    • [misc] Fix crash if optional python deps are missing.

    Miscellaneous

    • [core] Use dynamic and non-contiguous memory for telemetry.
    • [misc] Update easy install dependencies ahead of deployment.
    • [misc] Refactor CI to test building extension from pip install.
    Source code(tar.gz)
    Source code(zip)
  • 1.7.10(May 10, 2022)

    This release brings some minor performance improvements. The dependency management in Python has been rationalized to allow users to select desired features and prevent version incompatibilities. Support of Python 3.10 have been prepared to be distributed as soon as wheels for all dependencies will be available. Finally, deprecated documentation has been updated.

    Improvements

    • [core] Minor speed up of the constraint solver.
    • [core] Speed up computation of 'JMinvJt' required for constraint solving.
    • [core] Use same formula to compute tolerance for stepper and contact solver.
    • [misc] Meshcat and Matplotlib are now an optional requirements (meshcat,plot).

    Patches and bug fixes

    • [core] Update gravity attribute of theoretical model to match options.
    • [core/python] HeightMapFunctor raises an exception if an output is unset.
    • [python/viewer] Fix replay of multiple trajectories.

    Miscellaneous

    • [python/viewer] Do not enforce 'spawn' for meshcat.
    • [python] Class attributes that must be set at init are no longer considered Optional.
    • [misc] Fix support of avx2 instructions.
    • [misc] Fix jiminy cmake library path discovery after update.
    • [misc] Fix documentation and jupyter notebook tutorial.
    • [misc] Fix support of Python 3.10 while building from source.
    • [misc] Blacklist 'numpy>=1.21,<1.21.5' as it causes segfault of boost::python.
    • [misc] Easy install script for ubuntu is now container-friendly.
    Source code(tar.gz)
    Source code(zip)
  • 1.7.9(Apr 6, 2022)

    A few bugs that have been introduced in the previous release and earlier have been fixed. Exception handling has been improved to diagnose if something is going wrong with the physics.

    Patches and bug fixes

    • [core] Fix joint constraint reverse flag.
    • [core] Fix computation of ref contact position.
    • [core] Better handling of integration failure.
    • [core/python] Fix bindings class names and missing attributes.
    • [misc] Fix documentation generation.
    Source code(tar.gz)
    Source code(zip)
  • 1.7.8(Apr 6, 2022)

    A new custom constraint solver has been implemented. It is more reliable and convergences faster (less than 10 iterations most of the time). The speed is about the same as before the addition of friction cone and maximum energy dissipation. Hardware compatibility issues of Panda3d with some integrated Intel GPU have been addressed and off-screen parallel rendering is now supported. Finally, the recording speed has been greatly improved with Panda3d (x2).

    New features

    • [core] Add random sensor jitter.
    • [python/viewer] Add synchronous panda3d backend for subprocess rendering.
    • [python/viewer] Support opening viewer without robot.

    Improvements

    • [core] Faster and more reliable constraint solver.
    • [core] Avoid discontinuities at init by starting with contact enabled and adding transitionEps for joint bounds.
    • [core] Faster computation of extra terms (subtree inertias and com, centroidal dynamics)
    • [python/viewer] Dynamic update of available/default backend.
    • [python/viewer] Speed-up x2 replay video recording for panda3d backend.
    • [gym/common] Automatically render ground profile.

    Patches and bug fixes

    • [core] Fix potential mismatch between collision pairs and constraints.
    • [core] Fix engine not reset at start if not done before.
    • [core] Initialize stepper with smallest timestep to avoid peaks at init.
    • [core] Enable config baumgarte freq for user-specified constraints.
    • [core] Remove dedicated tolerance for PGS solver.
    • [python/viewer] Fix support of Intel GPU for rendering and on-demand Nvidia with panda3d.
    • [python/viewer] Default to sync panda3d backend if onscreen impossible.
    • [python/viewer] Disable shader in headless mode with panda3d to avoid segfault.
    • [python/viewer] Use physics-based shader on Intel GPU with Panda3d.
    • [gym/common] Fix init sensor data proxy and send llc command.
    • [gym/common] Use fastest modern rng 'SFC64'.

    Miscellaneous

    • [misc] Update ANYmal robot model.
    • [misc] Add support of Gym<0.24.0.
    • [misc] Fix support of ray==1.10.0
    Source code(tar.gz)
    Source code(zip)
  • 1.7.7(Mar 2, 2022)

    The overall stability and reliability has been improved, with a strong focus on the viewer. The support of 'gepetto-gui' has been dropped as it was platform-specific and missing key features.

    New features

    • [python/viewer] Drop support of 'gepetto-gui' backend. (#482)
    • [gym/common] Enable to provide custom robot to 'WalkerJiminyEnv'. (#477)

    Improvements

    • [core] Always regenerate original flexible model at reset to allow manual overwrite of rigid original model. (#475)
    • [python/viewer] Fallback to generic direct connection through ipykernel for Meshcat (VSCode, Jupyterlab). (#479)
    • [python/viewer] More robust comm filtering for executing meshcat related requests out of order. (#479)
    • [python/viewer] Speed up frame capture and reduce CPU load in offscreen mode for panda3d backend. (#481)
    • [gym/rllib] PPO supports dict and box spaces for observation/action. (#474)

    Patches and bug fixes

    • [core] Fix segfault when adding unspecified constraint. (#476)
    • [core] Fix 'buildReducedModel' for pinocchio < 2.6.0. (#477)
    • [core] Fix segfault when initializing engine with null robot. (#477)
    • [python/viewer] Fix connection to existing meshcat process. (#479)
    • [python/viewer] Fix random segfault at exit for synchronous panda3d backend. (#484)
    • [gym/rllib] PPO L2 reg only on train params. (#485)

    Miscellaneous

    • [gym/rllib] Refactor PPO implementation to support 'ray>=1.10.0'. (#474) (#485)
    • [misc] Use Ctest for managing C++ unit tests. (#475)

    Co-authored-by: Alexis Duburcq [email protected]

    Source code(tar.gz)
    Source code(zip)
  • 1.7.6(Dec 10, 2021)

    The focus of the release was making the contact model more realistic in Jiminy. As a reminder, it is formulated at acceleration level instead of velocity-level with impulse contact forces. The contact solver has been revamped to improve convergence, to ensure isotropic coulomb friction cone, and to follow maximum energy dissipation principal (except during the short transient sliding/sticking, or for dominant non-linear acceleration effects such as Coriolis). Many long lasting bugs in C++ core and Python have been tracked down and fixed.

    New features

    • [core] Enforce isotropic solution for PGS. (#467)
    • [core] Compensate PGS bias to ensure maximum energy dissipation for tangential friction. (#468)
    • [python/viewer] Add 'frame' markers. (#464)
    • [gym/common] Add 'evaluate' method to evaluate a callback policy over a whole episode. (#453)

    Improvements

    • [core] Compute PGS error in residual space. (#462)
    • [core] PGS skip parameter update if irrelevant. (#464)
    • [core] Force sensors now measure total external force applied on a body.
    • [core] Split constraint and contact options. (#462)
    • [core] Move to next breakpoint if possible to avoid very small timesteps during integration. (#464)
    • [python/viewer] Add support of 'pin.SE3' object for marker pose. (#465)
    • [python/viewer] Support specifying marker orientation using rotation matrix. (#464)

    Patches and bug fixes

    • [core] Fix non-linear PGS solving of friction cone. (#461)
    • [core] Fix 'removeContactPoints' if input vector is empty.
    • [core] Fix timestep adjustment for fixed timestep euler explicit stepper. (#464)
    • [core] Fix baumgarte stabilization of orientation for 'FixedFrameConstraint'. (#465)
    • [core] Fix json dump for empty dictionary. (#466)
    • [core] Remove random permutation from PGS since preserving order is important. (#467)
    • [core] Fix 'JointConstraint' position difference not properly computed. (#469)
    • [core] Fix telemetry header to null terminate leading to segfault. (#469)
    • [core] Fix inconsistency between flexible model and data. (#469)
    • [python/log] Fix segfault when loading robot from log. (#466)
    • [python/viewer] Exception handling and timeout if backend recorder for meshcat fails to open. (#452)
    • [python/viewer] Avoid crashing when replying simulations with 'nan'. (#458)
    • [python/viewer] Fix extraction of available sensor data for replay. (#463)
    • [python/viewer] Keep floor hidden even if updated if it was previously hidden for panda3d backend. (#463)
    • [python/viewer] Fix 'display' method if velocity is not provided. (#463)
    • [python/viewer] Fix body selection for panda3d. (#465)
    • [python/viewer] Do not overwrite color for 'frame' marker by default. (#464)
    • [gym/common] Improve exception handling during 'step'. (#458)
    • [gym/common] Do not try to register action to telemetry if empty.
    • [gym/envs] Reduce KD gain for AkY joints of Atlas to prevent numerical instability. (#464)

    Miscellaneous

    • [core] Use 'impulse' contact model as default. (#462)
    • [core] Modify 'FixedFrameConstraint' to set ground normal instead of local rotation. (#464)
    • [core] Order 'FixedFrameConstraint' components by solving order. (#467)
    • [gym/common] Rename 'refresh_*' in 'initialize_' when appropriate. (#466)
    • [gym/common] Rename 'refresh_internal' in 'refresh_buffers' and add 'initialize_buffers' method. (#466)
    • [gym/envs] Automatically detect relevant contact points for Atlas. (#464)
    • [misc] Update python packages description and development status. (#458)
    • [misc] Run unit tests in debug mode on Ubuntu 20.04. (#469)

    Co-authored-by: Alexis Duburcq [email protected]

    Source code(tar.gz)
    Source code(zip)
  • 1.7.5(Nov 21, 2021)

    This release is mainly intended to improve the support of Mac OS X >= 10.14 (Mojave). Now it is on a par with other platforms, with CI configured to run the unit tests on it. It also fixes a bunch of bugs concerning the viewer and the import of jiminy_py itself for developer users.

    Improvements

    • [viewer] 'add_markers' now forward positional arguments.
    • [viewer] Interrupt replay without crashing the display window for all backends.
    • [misc] Significant wheels size reduction (~20Mo for each architecture now).
    • [misc] Enable python unit tests on OSX.

    Patches and bug fixes

    • [core] Fix sphere constraint.
    • [viewer] Fix meshcat port detection on OS X.
    • [viewer] Disable physics-based shader is no discrete NVIDIA GPU to avoid graphic glitches. (#448)
    • [viewer] Force using 'spawn' multiprocessing context for meshcat to avoid crashes on OS X.
    • [viewer] Fix 'ipykernel' version detection on some setups.
    • [simulator] Fix wrong 'viewer.f_external' forces if render without simulation running.
    • [misc] Fix import of jiminy if boost is installed on the system but not pinocchio/hppfcl/eigenpy.

    Miscellaneous

    • [misc] Fix warnings using 'clang' compilation toolchain.
    • [misc] Build shared libs for boost python dependencies on unix to fix binding issues on OS X.
    • [misc] Fix jiminy pywrap copied twice in OS X wheels.
    • [misc] Build only universal2 wheel on OSX whenever possible.
    • [misc] Fix desired chromium version used by pyppeteer being ignored.
    • [misc] Update chromium version used by pyppeteer for the latest one available of any platform.
    • [misc] Fix OS X wheels deployment on Pypi. (#446)
    • [misc] Upgrade python dependencies.
    Source code(tar.gz)
    Source code(zip)
  • 1.7.4(Nov 12, 2021)

    Some limitations of Jiminy have been addressed. First, the friction pyramid has been replaced by an actual friction cone for the impulse contact model. Secondly, it is now possible to simulate a flexible model and impulse contact without numerical instability by introducing a new armature-like inertia parameter. Next, the viewer now uses a physics-based shader for Panda3D backend and a bunch of display issues have been fixed. Finally, it is the first release to officially support OS X, including arm Apple M1 CPU. Pre-compiled binaries are distributed on pypi.

    New features

    • [core] Implement friction cone for impulse model. (#440)
    • [core] Fix numerical instability of flexibility model by adding armature-like inertia parameter. (#433)
    • [python/viewer] Add physic based rendering of materials to panda3d.
    • [misc] Initial support of Mac (#441)

    Patches and improvements

    • [core] Full support of armature for all joints but mimic.
    • [python/viewer] Change direction of lighting in panda3d to fell natural for default camera pose.
    • [python/viewer] Enhanced rendering in panda3d for discrete gpu.
    • [python/viewer] Render meshes two-sided in panda3d to avoid seeing through them.
    • [gym/rllib] Add option to forward keyword arguments to 'ray.init'. (#436)

    Bug fixes

    • [python/robot] Fix default hardware config file generator is both collision and visual meshes are defined.
    • [python/viewer] Fix shadow casting area smaller than floor in panda3d.
    • [python/viewer] Fix window name not set properly in panda3d.

    Miscellaneous

    • [core] Rename 'pncCollisionData' to 'collisionData' and 'pncModelRigidOrig_' to 'pncModelOrig_'.
    • [core] Fix some implicit type conversions.
    • [misc] Update Python dependencies.
    • [misc] Update Boost from 1.7.1 to 1.7.6.
    • [misc] Build OSX wheels. (#442)
    Source code(tar.gz)
    Source code(zip)
  • 1.7.3(Oct 27, 2021)

    The simulator and viewer is now compatible with robots created manually from scratch without relying on URDF. Additionally, PGS solver with default parameters is now much faster thinks to SIMD vectorization and lower accuracy. The provided Cassie and Atlas environment have been tuned to improve the real time factor, which is now close to 50 on a single core.

    New features

    • [core] Enable to initialize 'jiminy::Robot' pinocchio models directly..
    • [python/robot] Enable to load hardware config on existing robot.
    • [gym/envs] Add atlas env with fixed upper body.

    Improvements

    • [core] Faster PGS solver. (#423)
    • [core] Add dedicated contact solver options 'tolAbs', 'tolRel'. (#424)
    • [core] Add 'name' getter to 'jiminy::Model', which is a proxy for URDF name.
    • [core] Add visual model to 'jiminy::Model' to avoid relying on URDF for rendering
    • [core/python] Add helper method to build reduced model.
    • [python] Do not rely on 'Robot.urdf_path' anymore.
    • [python/robot] Check if motors and sensors defined in hardware file can be added successfully.
    • [gym/common] Make sure the provided neutral configuration is valid.

    Patches and bug fixes

    • [core] Fix wrong computation of external forces.
    • [python/dynamics] Fix 'compute_freeflyer_state_from_fixed_body' method if fixed body is not provided.

    Miscellaneous

    • [gym/envs] Tune Cassie and Atlas to improve numerical stability using impulse contact model.
    • [misc] Fix support of matplotlib >= 3.4.
    • [misc] Stricter gym_jiminy optional deps requirements. (#425)
    • [misc] Fix gym_jiminy wheels deployement on pypi (again!).
    • [misc] Fix documentation generation.
    Source code(tar.gz)
    Source code(zip)
  • 1.7.2(Oct 19, 2021)

    Minor release mainly fixing bugs introduced recently.

    New features

    • [core] Add 'orientation' parameter 'randomTileGround' generator.

    Improvements

    • [gym/common] Render ground profile automatically during 'play_interactive'.

    Patches and bug fixes

    • [core/python] Fix python bindings of 'resetRandomGenerators' method.
    • [core/python] Fix assert in debug.
    • [python/simulation] Fix 'seed' method not resetting the generator if the seed does not change.
    • [python/viewer] Close panda3d viewer cleanly.
    • [gym/rllib] Fix PPO for 'enable_adversarial_noise' = False and 'caps_global_reg' == 0.0.

    Miscellaneous

    • [misc] Build wheels for manylinux2014 instead of manylinux2010 because of 'dm-tree'.
    • [misc] Build in Release and Debug on Ubuntu CI.
    Source code(tar.gz)
    Source code(zip)
  • 1.7.1(Oct 16, 2021)

    Random terrain generation tools have been translated from Python to C++ to significantly improve efficiency. New utilities to merge and sum random tile ground has been added to generate feature-rich ground profiles without noticeable slowdown wrt flat ground. In addition, it has been made easier to register new variables to the telemetry dynamically and retrieve data from logfiles.

    Nota bene: gym_jiminy release were not deployed on pypi since 1.6.27. This problem has been fixed now but there is no plan to add back the missing ones.

    New features

    • [core] Add tools to merge and sum heightmaps.
    • [gym/common] Add 'BaseJiminyEnv.register_variable' method easily log variables.
    • [gym/rllib] Add adversarial obs perturbation sampling for spatial regularization. (#414)

    Improvements

    • [core] Write terrain generation tools in C++ for efficiency.
    • [core] Enable to re-initialize controllers.
    • [core/python] It is now possible to extract raw python function from 'HeightMapFunctor' if any.
    • [python/viewer] Faster ground profile rendering.
    • [python/viewer] Do not render ground profile if original flat ground.
    • [gym/common] Generic structured space handling by relying on 'dm-tree' package.
    • [gym/common] Support any observation space in gym pipelines.

    Miscellaneous

    • [core] Rename 'HeatMap' in 'Heightmap'.
    • [misc] Fix CI not pushing gym_jiminy wheels on pypi.
    Source code(tar.gz)
    Source code(zip)
  • 1.7.0(Oct 10, 2021)

    Up to now, several key features were missing for the impulse-based LCP contact model to support most cases, and LCP solver was not mature enough to ensure smooth continuous dynamics. The impulse contact model now can handle any contact normal, which makes it suitable for uneven grounds. Moreover, a fast random tile ground generator has been added to easily create parametric challenging environments suitable for curriculum learning. Ultimately, the rendering of engine ground profile is now fully integrated in the viewer for panda3d backend. It will automatically renders the actual ground profile during replay of simulations. The minor release tag has been updated to highlight that impulse contact model is no longer experimental.

    New features

    • [core] Add support of torsional friction and contact normal to impulse contact model.
    • [python/generator] Add random tile ground profile generator.
    • [python/viewer] Add support of contact frames display.
    • [python/viewer] Add method to render floor based on 'HeatMapFunctor'.
    • [python/simulator] 'replay' now display the ground profile used by the engine.
    • [gym/rllib] Add temporal barrier regularizer to PPO.

    Improvements

    • [core] Move init of contact solver in reset instead of setOptions.
    • [core] Proper default 'stabilizationFreq' for impulse contact model.
    • [core] 'engine_options.contacts.stabilizationFreq' only applies to contact constraints.
    • [python/viewer] 'update_floor' method in panda3d now expects numpy array instead of callable to fix serialization issues.
    • [python/viewer] Speedup rendering of ground profile and improve visual by providing normal to panda3d.
    • [python/viewer] Add option to enable/disable display of ground profile meshes.
    • [python/simulator] Do not reset camera pose if gui already available.

    Patches and bug fixes

    • [python/robot] Fix support of URDF model with a single link for automatic hardware config generation.
    • [python/viewer] Add support of ipykernel 6 for meshcat backend interactive display.
    • [python/dynamics] Mitigate a weird segfault in pinocchio bindings of 'centerOfMass' method.
    • [gym/common] Fix automatic telemetry registration of the action.

    Miscellaneous

    • [gym/envs] Set baumgarte frequency for cassie internal constraints.
    • [misc] Enforce scipy>=1.2.0 to fix buggy optimizer.
    • [misc] Update 'typing_extensions' required version to fix pylint support for Python 3.6.
    Source code(tar.gz)
    Source code(zip)
  • 1.6.30(Sep 27, 2021)

    Meshcat viewer backend was mostly unmaintained since a year and was partially broken. This should now be fixed, with the addition of 3D rendering directly inside local VSCode notebooks and local Jupyterlab !

    New features

    • [python/viewer] Add height map rendering capability to Panda3d backend.
    • [python/viewer] Add support of jupyterlab and vscode notebooks locally using Meshcat backend.
    • [gym/common] Add flag to 'play_interactive' to ignore 'is_done' state.
    • [gym/rllib] Support obs normalization for PPO spatial regularization.
    • [gym/rllib] Scale spatial loss by observation distance.

    Improvements

    • [core] Shuffle constraint solver iterations iif necessary, no matter if constraint set changes.
    • [core] Move contact point at the interface with the ground for impulse model. (#404)
    • [python/viewer] Properly close opening viewer if raises exception at init.
    • [gym/common] Check that simulation data is available before plotting.
    • [gym/rllib] Raise clear exception if observation space is not dict in PPO.
    • [gym/rllib] Replace L2-norm temporal smoothness regularization by L1-norm.

    Patches and bug fixes

    • [core/python] Fix bindings signature of some controller's method.
    • [python/plot] Fix missing grid for single plot tabs.
    • [python/viewer] Fix viewer compatibility with meshcat>=0.3.1.
    • [python/viewer] Fix meshcat viewer 'has_gui' method.
    • [python/viewer] Fix meshcat notebook viewer.
    • [gym/common] Fix 'play_interactive' not disabling 'is_training' flag.
    • [gym/rllib] Fix L2 reg not backpropagating gradient.

    Miscellaneous

    • [python/viewer] Increase meshcat recorder timeout.
    • [misc] Fix CI dependency install.
    • [misc] Relax ray version requirement.
    Source code(tar.gz)
    Source code(zip)
  • 1.6.29(Aug 18, 2021)

    Small release fixing reproducibility issues, and updating RLlib tools to make it easier to assess and compare performance between policies.

    New features

    • [gym/common] Add train and eval modes to allow specific evaluation behaviors.
    • [gym/rllib] Add l2 regulization loss to PPO.
    • [gym/rllib] Enable to evaluate policy on multiple trials and report statistics.

    Improvements

    • [gym/common] 'seed' method now return the actual sequence of seeds instead of only the first one.
    • [gym/common] Do not cast automatically the action space to float32. (#400)
    • [gym/toolbox] Add 'quat_to_yaw_cos_sin' math helper.
    • [gym/rllib] Use noisy samples instead of the true ones to compute global smoothness.
    • [gym/rllib] Make sure the validation is always the same to make it easier to benchmark performance.

    Patches and bug fixes

    • [core] Fix log buffer not refreshed after calling 'stop', making last datapoint not accessible. (#396)
    • [python/robot] Fix non-reproducible simulation results.
    • [python/simulator] Fix running simulation not stopped before updating seed.
    • [python/simulator] Fix unexpected error if 'replay' is called without data.
    • [gym/common] Ensure internal '_action' buffer dtype float64. (#400)

    Miscellaneous

    • [gym/common] Do not set the seed by default in '_setup' method.
    • [gym/common] Rename '_is_training' in 'is_training'. Fix 'is_training' False by default. (#397)
    • [gym/common] Remove useless conversion of iterator to list.
    • [gym/rllib] Relax ray dependency version requirement.
    Source code(tar.gz)
    Source code(zip)
  • 1.6.28(Aug 4, 2021)

    This release fixes a new non-critical bugs and contains some minor improvements for gym tools suite.

    Improvements

    • [gym/common] More efficient random number generator.
    • [gym/common] Reset internal '_info' buffer before calling 'is_done' to enable storing extra info. (#386)
    • [gym/common] Faster space 'clip' utility.
    • [gym/common] Do not automatically disable telemetry anymore.
    • [gym/common] Enable 'refresh_observation' to access up-to-date shared internal data. (#384)
    • [gym/common] '_setup' updates frame kinematics for neutral configuration by default.
    • [gym/toolbox] Add more convex hull utilities.
    • [gym/toolbox] Add math utilities to extract yaw only from transform.

    Patches and bug fixes

    • [core] Fix model parameters random sampling.
    • [core] Make sure random physics parameters are valid.
    • [python/simulator] Fix default external force display during replay.
    • [python/viewer] Fix support of robot without sensors nor freeflyer.
    • [python/viewer] Check that 'time_interval' is valid. Fix out-of-range edge case.
    • [gym/common] Various minor bug fixes.
    • [gym/toolbox] Fix computation of distance from convex hull.
    • [gym/rllib] Fix connection of existing ray cluster head.
    • [gym/rllib] Clip random obs to space bounds in PPO regularization.
    • [gym/rllib] Fix support of non-dict obs space for 'build_policy_wrapper'.

    Miscellaneous

    • [misc] Add mass fixed frame with visual to cartpole.
    • [misc] Disable warnings when building SOUP. (#378)
    • [misc] Fix push gym_jiminy wheels on pypi. (#379)
    • [misc] Fix support of python virtual env for easy-install script. (#383)
    Source code(tar.gz)
    Source code(zip)
  • 1.6.27(Jul 12, 2021)

    All unnecessary copies and function calls in learning pipelines are now avoided. In additional, Python architecture has been refactored to reduce dependencies of main packages jiminy_py, gym_jiminy_common, and gym_jiminy_toolbox.

    New features

    • [gym/common] Allow to specify custom observer update period for base env to avoid refresh observation during internal steps.
    • [gym/common] Add optional '_refresh_internal' method to share computation between 'is_done' and 'compute_reward'.

    Improvements

    • [gym/common] Improve performance by avoiding deepcopy of action in 'compute_command' methods.
    • [gym/toolbox] More versatile compute action helper for rllib. (#373)

    Patches and bug fixes

    Miscellaenous

    • [python] Remove unused/unmaintained 'smoothing_filter' processing helper.
    • [misc] More generic github action wheel generation script. (#375)
    • [misc] Move 'processing' module from 'jiminy_py' to 'gym_jiminy.toolbox' to remove numba deps.
    • [misc] Move 'rllib' module from 'gym_jiminy.toolbox' to a dedicated 'gym_jiminy.rllib' package to remove rllib deps.
    Source code(tar.gz)
    Source code(zip)
  • 1.6.26(Jul 11, 2021)

    Small release fixing a few minor bugs.

    Improvements

    • [python/dynamics] Remove useless joint jacobians computation.

    Patches and bug fixes

    • [core/python] Fix bindings of pinocchio overloads.
    • [python/viewer] Fix calls to super in Panda3dQWidget (#370)
    • [misc] Do not try pushing legacy wheels on pypi. (#368)
    Source code(tar.gz)
    Source code(zip)
  • 1.6.25(Jul 6, 2021)

    Maintenance update fixing minor bugs. Some pre-compiled dependencies have been updated.

    Improvements

    • [core] Compute centroidal dynamics derivative systematically. (#365)
    • [gym/toolbox] Refactor Rllib PPO to always perform a single forward pass. (#366)

    Patches and bug fixes

    • [core] Fix computation of external forces. (#365)
    • [core/python] Fix wrong output array shape for single row or single element eigen matrix.

    Miscellaenous

    • [core] Fix eigen stack memory alignment for support of AVX2 instructions.
    • [misc] Add legacy build of jiminy wheel for python 3.8 (numpy<1.20).
    • [misc] Update dependencies (eigenpy==2.6.4, hppfcl==1.7.4).
    • [misc] Fix wheel manylinux seperated artefacts generation. (#364)
    Source code(tar.gz)
    Source code(zip)
  • 1.6.24(Jul 2, 2021)

    Another minor release, focusing only on improving performance of constrained inverse dynamics implementation. A very significant speedup by a factor 5 or 10 can be expected.

    Improvements

    • [core] Increase efficiency of inverse dynamics in Python.

    Patches and bug fixes

    • [python/viewer] Fix edge case when default-initializing viewer for theoretical model.
    Source code(tar.gz)
    Source code(zip)
  • 1.6.23(Jun 30, 2021)

    Fix several bugs introduced in previous release.

    Patches and bug fixes

    • [core] Fix segfault and compilation bug on Windows.
    • [python/dynamics] Fix wrong application point for spatial velocity and acceleration frames.
    • [python/viewer] Fix viewer edge cases when displaying several robots at once.
    • [python/viewer] Fix legend aspect ratio in Panda3d, and display it in line at bottom.
    • [python/viewer] Fix clock widget for Panda3d.
    • [gym/toolbox] Fix edge case in curriculum task scheduler.
    Source code(tar.gz)
    Source code(zip)
  • 1.6.22(Jun 19, 2021)

    This release introduces several experimental reinforcement learning features, along with a new inverse dynamics helper. A few bugs long-lasting bugs and inconsistencies in core have finally been addressed.

    New features

    • [python/dynamics] Add inverse dynamics helper.
    • [gym/toolbox/rllib] Add policy symmetry regularization to PPO.
    • [gym/toolbox/rllib] Add discrete hierarchical task space curriculum sampling.

    Improvements

    • [core] Expose 'Model.computeConstraint' in Python bindings.
    • [core] Do not update forward kinematics (position) in 'Robot.computeConstraints'.
    • [python/dynamics] Simplify helpers to take advantage of new pinocchio features.
    • [gym/toolbox/rllib] Automatically connect to existing cluster if any.
    • [gym/toolbox/rllib] Add helper to restore policy without trainer nor ray redis.
    • [gym/toolbox/rllib] Add memory tracing for memory leaks in debug mode.

    Patches and bug fixes

    • [core] Fix memory leaks in Eigen->Numpy Python bindings.
    • [core] Rename 'Model.hasConstraint' in 'Model.hasContraints' for consistency.
    • [core] Fix motor armatures not properly propagated after setting motor options.
    • [python/dynamics] Replace pinocchio methods by jiminy core overloads when appropriate.

    Miscellaneous

    • [python] Add some missing documentations.
    • [misc] Fix python executable detection on manylinux sometimes finding pypy instead of cython.
    • [misc] Updating gitignore to support use of virtual environment.
    Source code(tar.gz)
    Source code(zip)
  • 1.6.21(Jun 12, 2021)

    This release introduces a set of reinforcement learning tools based on ray[rllib]. In addition, it is now easier to replay and compare trajectories in different formats (sequence of states, log files, log data, and current simulation).

    New features

    • [python/simulator] Replay extra logs/trajectories with current simulation.
    • [gym/toolbox/rllib] Add dedicated rllib toolbox.
    • [gym/toolbox/rllib] Provide PPO CAPS implementation.

    Improvements

    • [python/viewer] Refactor Panda3d backend screen refresh and Qt widget to avoid edge cases.
    • [gym/toolbox/rllib] Do not provide default log dir since it is error prone
    Source code(tar.gz)
    Source code(zip)
  • 1.6.20(Jun 12, 2021)

  • 1.6.19(Jun 8, 2021)

    The interactive mode of gym_jiminy, allowing to play with a robot during a simulation using mouse and keyword input, has been greatly improvement in terms of features, reliability, and computational efficiency. Besides, every minor framerate drops of the viewer using Panda3d has been addressed to make the experience more enjoyable. It is now possible to replay more than 10 log files using integrated graphics at solid 30fps.

    New features

    • [python/viewer] Add option to not lock camera pose but only look-at point when travelling is enabled using Panda3d.

    Improvements

    • [python/viewer] Display freeflyer external forces by default.
    • [python/viewer] Add getter for camera pose.
    • [python/viewer] Improve viewer refresh efficientcy by only forcing display update whenever necessary.
    • [python/viewer] Add support of frame index to define relative lookup and camera pose.
    • [python/viewer] Add repeat capability to 'jiminy_replay' entrypoint.
    • [gym/common/envs] More versatile interactive loop helper.
    • [gym/common/envs] Add support of gym.wrappers to 'play_interactive'.
    • [gym/common/envs] Add 'pause' key to play interactive mode.

    Patches and bug fixes

    • [python/robot] Fix external forces not properly shared with viewer.
    • [python/viewer] Fix interactive loop CPU throttle by adding short sleep in deamon reading stdin.
    • [python/viewer] Mix busy loop and timer sleep in precise sleep to release the GIL.
    • [gym/common/envs] Fix simulation not stopped when playing ends in play interactive mode.

    Miscellaneous

    • [gym/examples/rllib] Provide helper to wrap policy as callable[[observation, reward], action].
    Source code(tar.gz)
    Source code(zip)
  • 1.6.18(Jun 3, 2021)

    This release only consists of minor quality-of-life improvements. In addition, a few bugs in Jiminy viewer have been fixed, and a more robust initial guess is provided to the 'impulse' contact solver to improve continuity of contact forces.

    Improvements

    • [core] Provide robust initial guess to 'impulse' contact solver.
    • [gym/common] 'sample' now supports providing both 'shape' and vector 'low'/'high'/'mean'/'scale' if broadcastable.

    Patches and bug fixes

    • [python/viewer] Fix clicking on node for panda3d Qt widget.
    • [python/viewer] Fix seldom lock issues when displaying many robots simultaneously.

    Miscellaneous

    • [gym/examples/rllib] Start ray backend in local mode in debug.
    • [gym/examples/rllib] More robust observation flattening.
    • [gym/examples/rllib] Interrupt learning gracefully in case of ray task exception.
    • [gym/examples/rllib] Do not replay if recording is disable during training.
    • [gym/examples/rllib] Add option to use custom logger.
    • [gym/examples/rllib] Add option to save checkpoint every given number of training iterations.
    Source code(tar.gz)
    Source code(zip)
  • 1.6.17(May 18, 2021)

    Very small release primarily intended to fix a bunch of bugs introduced in the previous ones. In addition, user-specified standard deviation for model parameters is now relative instead of absolute to be more consistent with the literature, and 'EngineMultiRobot.start' method no longer force reset of the simulation, giving more flexibility to the user, for example to run several simulations using the same model.

    Improvements

    • [core] 'EngineMultiRobot.Start' no longer reset the engine automatically.
    • [core] Biases for random model generation are now relative instead of absolute.
    • [python/viewer] Log replay now support overwriting mesh package dir.
    • [gym/example] Add option to specify log subdirectory name interactively.

    Patches and bug fixes

    • [core] Fix computation of center of mass positions and velocities.
    • [python/viewer] Fix log replay without velocity and external forces data available.

    Miscellaneous

    • [misc] Fix CI numpy version issues.
    Source code(tar.gz)
    Source code(zip)
  • 1.6.16(May 17, 2021)

    Following the previous release, this one adds new markers to help analyze simulations, especially for locomotion tasks of bipedal robots. It is now possible to display the Capture Point (also called DCM) and external forces. Besides, Reinforcement Learning tools based on RLLib have been improved and a few bugs have been fixed.

    New features

    • [python/processing] Add convex hull utilities.
    • [python/viewer] Add option to display DCM in viewer.
    • [python/viewer] Add option to display external linear forces at joint level in viewer.

    Improvements

    • [core] Add option to register external forces to the telemetry.
    • [core] Compute velocity of the center of mass of each subtree systematically.
    • [python/processing] Improve efficiency and versatility of 'interpolate_zoh'.
    • [python/log] Extract external forces from log if recorded.
    • [python/viewer] Improve efficiency of markers update.
    • [python/viewer] 'jiminy_replay' entrypoint can now be used to record video.
    • [gym/examples] Add monitoring of episode duration.

    Patches and bug fixes

    • [core] Fix internal update period computation when defined control and sensor update period of the engine without robot.
    • [python/robot] Add fallback if 'dynamics' fields 'damping'/'friction' are partially defined in URDF file.
    • [python/viewer] Fix default display marker value if backend is not Panda3d.
    • [gym/examples] Fix logging performance issues of RLlib.

    Miscellaneous

    • [gym/examples] Improve documentation of RLlib tools.
    Source code(tar.gz)
    Source code(zip)
Box - a world simulator written in python with pygame

Box is a world simulator written in python with pygame. Features A world generation system A world editor Simulates creatures called boxlanders. You c

1up Community 3 Nov 14, 2022
XPlaneROS is a ROS wrapper for the XPlane-11 flight simulator.

XPlaneROS XPlaneROS is a ROS wrapper for the XPlane-11 flight simulator. The wrapper provides functionality for extracting aircraft data from the simu

AirLab Stacks 26 Dec 4, 2022
Lutris helps you install and play video games from all eras and from most gaming systems.

Lutris Lutris helps you install and play video games from all eras and from most gaming systems. By leveraging and combining existing emulators, engin

Pop!_OS 2 Nov 15, 2021
The repository that hosts the code that teaches a reinforcement learning - based bot to play 2048

The repository that hosts the code that teaches a reinforcement learning - based bot (based on policy gradients method) to play 2048

Maxim Rud 1 Dec 16, 2021
Finding a method to objectively quantify skill expression in games, using reinforcement learning

Analyzing Skill Expression in Games This is a repo where I describe a method to measure the amount of skill expression games have. Table of Contents M

Marcus Chiam 4 Nov 19, 2022
Jogo da velha com interface gráfica desenvolvida em Python utilizando pygame e IA(Inteligência Artificial)

Jogo-da-Velha Sobre o projeto Jogo da velha com interface gráfica desenvolvida em Python utilizando pygame e IA(Inteligência Artificial) Layout tela d

Matheus Maia Alvarez 6 Apr 9, 2022
Chesston (Chess+Python) is a two-player chess game with graphical user interface written in PyQt5

♟️ Chesston (Chess+Python) is a two-player chess game with graphical user interface written in PyQt5. ?? Dependencies This program uses Py

null 6 May 26, 2022
PLVRA is a TUI (Terminal User Interface) implementation of wordle / termo in portuguese, written in Python

PLVRA is a TUI (Terminal User Interface) implementation of wordle / termo in portuguese, written in Python

Enzo Shiraishi 1 Feb 11, 2022
Fully functional BlackJack game with a graphical user interface.

BlackJack Welcome to BlackJack! This game is fully functional, with a casino sound package integrated using Pygame, dynamic game logic developed using

Shwetang Desai 2 Jan 10, 2022
A "guess the number" game on a GUI interface using Tkinter library🙂

A "guess the number" game on a GUI interface using Tkinter library??

Arsalan 2 Feb 1, 2022
Crazy fast kahoot game flooder with a GUI and multi OS support.

kahoot flooder Crazy fast kahoot game flooder with a GUI and multi OS support. Made in python using tkinter and KahootPY with toast notifications. Req

Ben Tettmar 1 Apr 9, 2022
A game developed while learning python

Alien_Invasion a game developed while learning python you must have python-3 installed in your computer. and pygame module is also required for this.

Jani Shubham 0 Oct 10, 2022
A "finish the lyrics" game using Spotify, YouTube Transcript, and YouTube Search APIs, coupled with visual machine learning

Singify Introducing Singify, the party game! Challenge your friend to who knows songs better. Play random songs from your very own Spotify playlist an

Josh Wong 4 Nov 19, 2021
Visualizing and learning from games on chess.com

Better Your Chess What for? This project aims to help you learn from all the chess games you've played online, starting with a simple way to download

Luc d'Hauthuille 0 Apr 17, 2022
Create a Hangman Game using Python and all techniques of Python.

Hangman Game Created by Fernando Callasaca Game rules: Choose a word and if you guess it will appear completed. In case it is not the word then the ma

Fernando Callasaca 3 Nov 1, 2021
pygame is a Free and Open Source python programming language library for making multimedia applications like games built on top of the excellent SDL library. C, Python, Native, OpenGL.

pygame is a Free and Open Source python programming language library for making multimedia applications like games built on top of the excellent SDL library. C, Python, Native, OpenGL.

pygame 5.6k Jan 1, 2023
Wordle-Python - A simple low-key clone of the popular game WORDLE made with python and a 2D Graphics module Pygame

Wordle-Python A simple low-key clone of the popular game WORDLE made with python

Showmick Kar 7 Feb 10, 2022
Python Knots and Crosses game, with customizable markers and more!

Knot-and-Crosses Python Knots and Crosses game, with customizable markers and more! Features: Ability to change your marker Ability to change how many

null 4 Nov 7, 2021
learn and have fun developing 2D retro games using python and pygame

Retro 2D Game Development Using Python + PyGame Skill up your programming skills with a walk down the memory lane. Learn how to create a retro 2D game

Marvin Trilles 1 Feb 23, 2022