Skip to content

Commit

Permalink
[python/plot] More versatile plotting tools. (#302)
Browse files Browse the repository at this point in the history
* [core|python] Add support of non-contiguous temporary to 'register_variables'. 
* [core/python] Allow registering 2D numpy arrays for bindings.
* [python/processing] Add N-order integrator assuming zero-order-hold for highest derivative.
* [python|gym] Add TabbedFigure class and use it in simulator. 
* [python|gym] Move '_log_data' from gym env to simulator. Log generic action automatically.
* [misc] Remove force install 'numba==0.53.0rc3' on CI since 0.53 is now available.
* [misc] Consistent use of 'resource_filename' to access models data.
* [misc] Add Atlas in Readme instead of Anymal.
* [misc] Fix ipython tutorial.
* [python/plot] Add option to sync tabs. Fix remove tab and clear figure.
* [python/simulator] Fix log backup cleanup.
* [python/simulator] Enable argument forwarding for 'plot' method.
* [misc] Fix type checker errors.
* [python/dynamics] Fix 'update_quantities' not calling forward kinematics when necessary. Compute everything between jacobians by default.
* [python/plot] Only refresh canvas when needed. 
* [python/plot] Automatically re-arrange subplot grid. 
* [python/plot] Add export methods. 
* [python/plot] Fix support of any backend. 
* [python/plot] Add partial documentation.
* [python/plot] Fix buttons responsiveness and active tab hovering color.
* [python/plot] Disable click button for active tab.
* [python/plot] Add 'close' method. 
* [python/plot] Add 'image_path' option argument to 'plot' method.
* [gym/common/pipeline] Fix controller wrapper not updating env action and not calling env 'compute_command'.

Co-authored-by: Alexis Duburcq <[email protected]>
  • Loading branch information
duburcqa and Alexis Duburcq authored Mar 20, 2021
1 parent 5538708 commit 3b8d2f1
Show file tree
Hide file tree
Showing 33 changed files with 939 additions and 385 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/linux.yml
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ jobs:
run: |
./build_tools/build_install_deps_linux.sh
"${PYTHON_EXECUTABLE}" -m pip install torch==1.8.0+cpu -f https://download.pytorch.org/whl/torch_stable.html
"${PYTHON_EXECUTABLE}" -m pip install "gym>=0.17.3,<0.18.0" "numba==0.53.0rc3" "stable_baselines3>=0.10"
"${PYTHON_EXECUTABLE}" -m pip install "gym>=0.17.3,<0.18.0" "stable_baselines3>=0.10"
PYTHON_USER_SITELIB="$("${PYTHON_EXECUTABLE}" -m site --user-site)"
mkdir -p "${PYTHON_USER_SITELIB}"
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/manylinux.yml
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ jobs:
- name: Build project dependencies
run: |
./build_tools/build_install_deps_linux.sh
"${PYTHON_EXECUTABLE}" -m pip install "gym>=0.17.3,<0.18.0" "numba==0.53.0rc3" "stable_baselines3>=0.10"
"${PYTHON_EXECUTABLE}" -m pip install "gym>=0.17.3,<0.18.0" "stable_baselines3>=0.10"
#####################################################################################

Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/ubuntu.yml
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ jobs:
run: |
sudo "${GITHUB_WORKSPACE}/build_tools/easy_install_deps_ubuntu.sh"
"${PYTHON_EXECUTABLE}" -m pip install "torch==1.8.0+cpu" -f https://download.pytorch.org/whl/torch_stable.html
"${PYTHON_EXECUTABLE}" -m pip install "gym>=0.17.3,<0.18.0" "numba==0.53.0rc3" "stable_baselines3>=0.10"
"${PYTHON_EXECUTABLE}" -m pip install "gym>=0.17.3,<0.18.0" "stable_baselines3>=0.10"
#####################################################################################

Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/win.yml
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ jobs:
- name: Build project dependencies
run: |
python -m pip install "torch==1.8.0+cpu" -f https://download.pytorch.org/whl/torch_stable.html
python -m pip install "gym>=0.17.3,<0.18.0" "numba==0.53.0rc3" "stable_baselines3>=0.10"
python -m pip install "gym>=0.17.3,<0.18.0" "stable_baselines3>=0.10"
& "./build_tools/build_install_deps_windows.ps1"
#####################################################################################
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.10)

# Set the build version
set(BUILD_VERSION 1.6.4)
set(BUILD_VERSION 1.6.5)

# Add definition of Jiminy version for C++ headers
add_definitions("-DJIMINY_VERSION=\"${BUILD_VERSION}\"")
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ Pre-configured environments for some well-known toys models and reference roboti
<img src="https://raw.github.com/duburcqa/jiminy/readme/jiminy_tensorboard_cartpole.png" alt="" width="98.5%"/>
<img src="https://raw.github.com/duburcqa/jiminy/readme/jiminy_learning_ant.gif" alt="" width="32.5%"/>
<img src="https://raw.github.com/duburcqa/jiminy/readme/cassie.png" alt="" width="32.5%"/>
<img src="https://raw.github.com/duburcqa/jiminy/readme/anymal.png" alt="" width="32.5%"/>
<img src="https://raw.github.com/duburcqa/jiminy/readme/atlas.png" alt="" width="32.5%"/>
</p>
</a>

Expand Down
4 changes: 2 additions & 2 deletions core/include/jiminy/core/control/AbstractController.h
Original file line number Diff line number Diff line change
Expand Up @@ -84,13 +84,13 @@ namespace jiminy
/// update it manually whenever it is necessary to do so.
///
/// \param[in] fieldnames Name of each element of the variable. It will appear in the header of the log.
/// \param[in] values Eigen vector to add to the telemetry
/// \param[in] values Eigen vector to add to the telemetry. It accepts non-contiguous temporary.
///
/// \return Return code to determine whether the execution of the method was successful.
///
///////////////////////////////////////////////////////////////////////////////////////////////
hresult_t registerVariable(std::vector<std::string> const & fieldnames,
Eigen::Ref<vectorN_t> values); // Make a "copy" to support both vectorN_t and reference
Eigen::Ref<vectorN_t, 0, Eigen::InnerStride<> > values); // Make a "copy" to support both vectorN_t and reference

///////////////////////////////////////////////////////////////////////////////////////////////
///
Expand Down
13 changes: 7 additions & 6 deletions core/include/jiminy/core/control/AbstractController.tpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,19 +15,20 @@ namespace jiminy
{
using std::to_string;

inline std::string to_string(char_t const * var)
{
return {var};
}

inline std::string to_string(Eigen::Ref<matrixN_t const> const & var)
template<typename DerivedType>
std::string to_string(Eigen::MatrixBase<DerivedType> const & var)
{
Eigen::IOFormat HeavyFmt(Eigen::FullPrecision, 0, ", ", ";\n", "[", "]", "[", "]");
std::stringstream matrixStream;
matrixStream << var.format(HeavyFmt);
return matrixStream.str();
}

inline std::string to_string(char_t const * var)
{
return {var};
}

///////////////////////////////////////////////////////////////////////////////////////////////
///
/// \brief Register a constant to the telemetry.
Expand Down
4 changes: 2 additions & 2 deletions core/src/control/AbstractController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ namespace jiminy
}

hresult_t AbstractController::registerVariable(std::vector<std::string> const & fieldnames,
Eigen::Ref<vectorN_t> values)
Eigen::Ref<vectorN_t, 0, Eigen::InnerStride<> > values)
{
// Delayed variable registration (Taken into account by 'configureTelemetry')

Expand All @@ -192,7 +192,7 @@ namespace jiminy
PRINT_ERROR("Variable already registered.");
return hresult_t::ERROR_BAD_INPUT;
}
registeredVariables_.emplace_back(*fieldIt, values.data() + i);
registeredVariables_.emplace_back(*fieldIt, &values[i]);
}

return hresult_t::SUCCESS;
Expand Down
32 changes: 21 additions & 11 deletions examples/tutorial.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -60,36 +60,46 @@
],
"source": [
"import os\n",
"from pkg_resources import resource_filename\n",
"\n",
"import numpy as np\n",
"\n",
"import jiminy_py.core as jiminy # The main module of jiminy - this is what gives access to the Robot and Engine class.\n",
"import jiminy_py.core as jiminy # The main module of jiminy - this is what gives access to the Robot\n",
"from jiminy_py.controller import BaseJiminyObserverController\n",
"from jiminy_py.simulator import Simulator\n",
"\n",
"\n",
"data_root_path = \"../data/toys_models/simple_pendulum\"\n",
"data_root_path = resource_filename(\n",
" \"gym_jiminy.envs\", \"data/toys_models/simple_pendulum\")\n",
"urdf_path = os.path.join(data_root_path, \"simple_pendulum.urdf\")\n",
"\n",
"# Instantiate and initialize the robot\n",
"robot = jiminy.Robot()\n",
"robot.initialize(urdf_path, mesh_package_dirs=[data_root_path])\n",
"\n",
"# Add a single motor\n",
"motor = jiminy.SimpleMotor(\"PendulumJoint\")\n",
"robot.attach_motor(motor)\n",
"motor.initialize(\"PendulumJoint\")\n",
"\n",
"# Create the controller: for now, the motor is off and doesn't modify the output torque.\n",
"# Instantiate and initialize the controller\n",
"controller = BaseJiminyObserverController()\n",
"controller.initialize(robot)\n",
"\n",
"# Set the command: for now, the motor is off and doesn't modify the output torque.\n",
"def compute_command(t, q, v, sensors_data, command):\n",
" command.fill(0.0)\n",
"controller.set_controller_handle(compute_command)\n",
"\n",
"# Create a simulator using this robot and controller\n",
"simulator = Simulator(robot)\n",
"simulator.controller.set_controller_handle(compute_command)\n",
"simulator = Simulator(robot, controller)\n",
"\n",
"# Set initial condition and simulation length\n",
"x0 = np.array([0.1, 0])\n",
"q0, v0 = np.array([0.1]), np.array([0.0])\n",
"simulation_duration = 10.0\n",
"\n",
"# Launch the simulation\n",
"simulator.run(simulation_duration, x0)"
"simulator.run(simulation_duration, q0, v0)"
]
},
{
Expand Down Expand Up @@ -2693,8 +2703,8 @@
"def compute_command(t, q, v, sensors_data, command):\n",
" command[:] = - Kp * (q + Kd * v)\n",
"\n",
"simulator.controller.set_controller_handle(compute_command)\n",
"simulator.run(simulation_duration, x0)\n",
"controller.set_controller_handle(compute_command)\n",
"simulator.run(simulation_duration, q0, v0)\n",
"\n",
"log_data, _ = simulator.get_log()\n",
"play_logfiles(robot, log_data, camera_xyzrpy=camera_xyzrpy)"
Expand Down Expand Up @@ -2740,7 +2750,7 @@
"\n",
"# Apply this force profile to a given frame.\n",
"simulator.engine.register_force_profile(\"PendulumMass\", force_profile)\n",
"simulator.run(simulation_duration, x0)\n",
"simulator.run(simulation_duration, q0, v0)\n",
"\n",
"log_data, _ = simulator.get_log()\n",
"play_logfiles(robot, log_data, camera_xyzrpy=camera_xyzrpy)"
Expand Down Expand Up @@ -2768,4 +2778,4 @@
},
"nbformat": 4,
"nbformat_minor": 4
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

import gym

from ..utils import FieldDictNested, SpaceDictNested
from ..utils import get_fieldnames, FieldDictNested, SpaceDictNested
from ..envs import BaseJiminyEnv
from .generic_bases import ControllerInterface, ObserverInterface

Expand Down Expand Up @@ -264,11 +264,14 @@ def get_fieldnames(self) -> FieldDictNested:
action space, the difference being numerical arrays replaced by lists
of string.
By default, generic fieldnames using 'Action' prefix and index as
suffix for `np.ndarray`.
.. note::
This method is not supposed to be called before `reset`, so that
the controller should be already initialized at this point.
"""
raise NotImplementedError
return get_fieldnames(self.action_space)


BaseControllerBlock._setup.__doc__ = \
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ def _controller_handle(self,
sensors_data: jiminy.sensorsData,
command: np.ndarray) -> None:
command[:] = self.compute_command(
self.env.get_observation(), self._action)
self.env.get_observation(), deepcopy(self._action))

def _get_block_index(self) -> int:
"""Get the index of the block. It corresponds the "deepness" of the
Expand Down Expand Up @@ -219,6 +219,7 @@ def compute_command(self,
:param action: Target to achieve.
"""
set_value(self._action, action)
set_value(self.env._action, action)
return self.env.compute_command(measure, action)


Expand Down Expand Up @@ -515,9 +516,10 @@ def _setup(self) -> None:

# Register the controller target to the telemetry.
# It may be useful for computing the terminal reward or debugging.
register_variables(
self.simulator.controller, self.controller.get_fieldnames(),
self._action, self.controller_name)
register_variables(self.simulator.controller,
self.controller.get_fieldnames(),
self._action,
self.controller_name)

def compute_command(self,
measure: SpaceDictNested,
Expand All @@ -534,9 +536,6 @@ def compute_command(self,
:param measure: Observation of the environment.
:param action: High-level target to achieve.
"""
# Backup the action
set_value(self._action, action)

# Update the target to send to the subsequent block if necessary.
# Note that `_observation` buffer has already been updated right before
# calling this method by `_controller_handle`, so it can be used as
Expand All @@ -554,8 +553,9 @@ def compute_command(self,
if self.simulator.is_simulation_running:
# Do not update command during the first iteration because the
# action is undefined at this point
set_value(self.env._action, self._target)
set_value(self._command, self.env.compute_command(
self._observation, self._target))
self._observation, deepcopy(self._target)))

return self._command

Expand Down
Loading

0 comments on commit 3b8d2f1

Please sign in to comment.