Skip to content

Commit

Permalink
[python] Add CLI to replay log files. (#334)
Browse files Browse the repository at this point in the history
* [core/python] Fix 'buildGeomFromUrdf' module interoperability.
* [python/simulator] 'simulate' now supports writing log in any available format.
* [python/log] Add generic utility to reconstruct robot from log.
* [python/viewer] Fix default legend when replaying multiple trajectories at once.
* [python/viewer] Add method to replay log file, only requiring the original meshes to be available.
* [python/viewer] Add 'jiminy_replay' CLI entrypoint to replay Jiminy log files.
* [python/viewer] Add option to not remove widgets after replaying trajectories. 
* [python/viewer] Reorder default colors cycle.
* [python/viewer] Switch device notifications from 'error' to 'fatal' for Panda3d.
* [python/viewer] Fix colors of Panda3d legend. 
* [python/viewer] Fix legend in panda3d when using identical labels. 
* [misc] Remove dual ABI support for Python bindings since it is unstable and may cause segfault.
* [misc] Provide cmake config version file in wheel.

Co-authored-by: Alexis Duburcq <alexis.duburcq@wandercraft.eu>
  • Loading branch information
duburcqa and Alexis Duburcq authored Apr 28, 2021
1 parent c2af825 commit a7e3aa9
Show file tree
Hide file tree
Showing 26 changed files with 575 additions and 324 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/manylinux.yml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ on:
jobs:
build-test-and-publish-pypi-manylinux:
name: >-
(${{ matrix.container }}) (Python${{ matrix.PYTHON_VERSION }})
(${{ matrix.container }}) (${{ matrix.PYTHON_VERSION }})
Build and run the unit tests. Then generate and publish the wheels on PyPi.
runs-on: ubuntu-20.04
container: quay.io/pypa/${{ matrix.container }}
Expand Down
9 changes: 8 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,14 @@
cmake_minimum_required(VERSION 3.10)

# Set the build version
set(BUILD_VERSION 1.6.13)
set(BUILD_VERSION 1.6.14)

# Set compatibility
if(CMAKE_VERSION VERSION_GREATER "3.11.0")
set(COMPATIBILITY_VERSION SameMinorVersion)
else()
set(COMPATIBILITY_VERSION ExactVersion)
endif()

# Extract major, minor and patch version
string(REPLACE "." ";" _VERSION "${BUILD_VERSION}")
Expand Down
12 changes: 6 additions & 6 deletions build_tools/cmake/base.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -69,10 +69,10 @@ set(EIGEN_MPL2_ONLY 1)

# Add a helper to link target libraries as system dependencies to avoid generating warnings
function(target_link_libraries_system target)
set(libs ${ARGN})
foreach(lib ${libs})
get_target_property(lib_include_dirs ${lib} INTERFACE_INCLUDE_DIRECTORIES)
target_include_directories(${target} SYSTEM PRIVATE ${lib_include_dirs})
target_link_libraries(${target} ${lib})
endforeach(lib)
set(libs ${ARGN})
foreach(lib ${libs})
get_target_property(lib_include_dirs ${lib} INTERFACE_INCLUDE_DIRECTORIES)
target_include_directories(${target} SYSTEM PRIVATE ${lib_include_dirs})
target_link_libraries(${target} ${lib})
endforeach(lib)
endfunction(target_link_libraries_system)
6 changes: 0 additions & 6 deletions build_tools/cmake/exportCmakeConfigFiles.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -22,12 +22,6 @@ function(exportCmakeConfigFiles)
DESTINATION "${CMAKE_INSTALL_DATADIR}/${LIBRARY_NAME}/cmake"
)

if(CMAKE_VERSION VERSION_GREATER "3.11.0")
set(COMPATIBILITY_VERSION SameMinorVersion)
else()
set(COMPATIBILITY_VERSION AnyNewerVersion)
endif()

write_basic_package_version_file(
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake
VERSION ${BUILD_VERSION}
Expand Down
16 changes: 0 additions & 16 deletions build_tools/cmake/jiminyConfig.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -62,22 +62,6 @@ if (NOT Python_NumPy_INCLUDE_DIRS)
HINTS "${__numpy_path}" "${Python_INCLUDE_DIRS}" NO_DEFAULT_PATH)
endif()

# Get jiminy version, and check if compatible with requested version, if any.
# For now, compatibility is assumed as long as only patch version differs.
execute_process(COMMAND "${Python_EXECUTABLE}" -c
"import jiminy_py; print(jiminy_py.__version__, end='')"
OUTPUT_VARIABLE jiminy_VERSION)
string(REPLACE "." ";" _VERSION "${jiminy_VERSION}")
list(GET _VERSION 0 jiminy_VERSION_MAJOR)
list(GET _VERSION 1 jiminy_VERSION_MINOR)
list(GET _VERSION 2 jiminy_VERSION_PATCH)
if (PACKAGE_FIND_VERSION_MAJOR)
if (PACKAGE_FIND_VERSION_MAJOR EQUAL jiminy_VERSION_MAJOR)
message(FATAL_ERROR "Available `jiminy_py` version (${jiminy_VERSION}) not "
"compatible with requested one (${PACKAGE_FIND_VERSION}).")
endif()
endif()

# Find jiminy library and headers.
# Note that jiminy is compiled under C++17 using either old or new CXX11 ABI.
# Make sure very project dependencies are compiled for the same CXX11 ABI
Expand Down
8 changes: 4 additions & 4 deletions core/include/jiminy/core/robot/Model.h
Original file line number Diff line number Diff line change
Expand Up @@ -364,9 +364,9 @@ namespace jiminy
vectorN_t & vRigid) const;

protected:
hresult_t loadUrdfModel(std::string const & urdfPath,
bool_t const & hasFreeflyer,
std::vector<std::string> meshPackageDirs);
hresult_t initialize(pinocchio::Model const & pncModel,
pinocchio::GeometryModel const & collisionModel);

hresult_t generateModelFlexible(void);
hresult_t generateModelBiased(void);

Expand Down Expand Up @@ -395,7 +395,7 @@ namespace jiminy
public:
pinocchio::Model pncModel_;
mutable pinocchio::Data pncData_;
pinocchio::GeometryModel pncGeometryModel_;
pinocchio::GeometryModel collisionModel_;
mutable std::unique_ptr<pinocchio::GeometryData> pncGeometryData_; // Using smart ptr to avoid having to initialize it with an empty GeometryModel, which causes Pinocchio segfault at least up to v2.5.6
pinocchio::Model pncModelRigidOrig_;
pinocchio::Data pncDataRigidOrig_;
Expand Down
21 changes: 15 additions & 6 deletions core/include/jiminy/core/utilities/Pinocchio.h
Original file line number Diff line number Diff line change
Expand Up @@ -103,12 +103,21 @@ namespace jiminy
frameIndex_t const & frameIdx,
pinocchio::Force const & fextInGlobal);

void buildGeom(pinocchio::Model const & model,
std::string const & filename,
pinocchio::GeometryType const & type,
pinocchio::GeometryModel & geomModel,
std::vector<std::string> const & package_dirs,
bool_t const & loadMeshes = false);
hresult_t buildGeomFromUrdf(pinocchio::Model const & model,
std::string const & filename,
pinocchio::GeometryType const & type,
pinocchio::GeometryModel & geomModel,
std::vector<std::string> const & packageDirs,
bool_t const & loadMeshes = true,
bool_t const & makeConvexMeshes = false);

hresult_t buildModelsFromUrdf(std::string const & urdfPath,
bool_t const & hasFreeflyer,
std::vector<std::string> const & meshPackageDirs,
pinocchio::Model & pncModel,
pinocchio::GeometryModel & collisionModel,
boost::optional<pinocchio::GeometryModel &> visualModel = boost::none,
bool_t const & loadVisualMeshes = false);
}

#endif // JIMINY_PINOCCHIO_H
36 changes: 25 additions & 11 deletions core/src/engine/EngineMultiRobot.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,9 @@
#include <unordered_set>
#include <algorithm>
#include <iostream>
#include <sstream>
#include <fstream>
#include <streambuf>

#include "pinocchio/parsers/urdf.hpp"

Expand Down Expand Up @@ -1401,26 +1404,37 @@ namespace jiminy
// Log systems data
for (auto const & system : systems_)
{
// Backup Robot's input arguments
std::string const telemetryUrdfPath = addCircumfix(
"urdf_path", system.name, "", TELEMETRY_FIELDNAME_DELIMITER);
telemetrySender_.registerConstant(
telemetryUrdfPath, system.robot->getUrdfPath());
// Backup URDF file
std::string const telemetryUrdfFile = addCircumfix(
"urdf_file", system.name, "", TELEMETRY_FIELDNAME_DELIMITER);
std::ifstream urdfFileStream(system.robot->getUrdfPath());
std::string const urdfFileString((std::istreambuf_iterator<char_t>(urdfFileStream)),
std::istreambuf_iterator<char_t>());
telemetrySender_.registerConstant(telemetryUrdfFile, urdfFileString);

// Backup 'has_freeflyer' option
std::string const telemetrHasFreeflyer = addCircumfix(
"has_freeflyer", system.name, "", TELEMETRY_FIELDNAME_DELIMITER);
telemetrySender_.registerConstant(
telemetrHasFreeflyer, std::to_string(system.robot->getHasFreeflyer()));

// Backup mesh package lookup directories
std::string const telemetryMeshPackageDirs = addCircumfix(
"mesh_package_dirs", system.name, "", TELEMETRY_FIELDNAME_DELIMITER);
std::string meshPackageDirsString;
for (std::string const & dir : system.robot->getMeshPackageDirs())
std::stringstream meshPackageDirsStream;
std::vector<std::string> const & meshPackageDirs = system.robot->getMeshPackageDirs();
copy(meshPackageDirs.begin(), meshPackageDirs.end(),
std::ostream_iterator<std::string>(meshPackageDirsStream, ";"));
if (meshPackageDirsStream.peek() != decltype(meshPackageDirsStream)::traits_type::eof())
{
meshPackageDirsString += dir + '\n';
meshPackageDirsString = meshPackageDirsStream.str();
meshPackageDirsString.pop_back();
}
telemetrySender_.registerConstant(
telemetryMeshPackageDirs, meshPackageDirsString);

// Backup the Pinocchio Model related to the current simulation
// Backup the Pinocchio Model used for the simulation
std::string const telemetryModelName = addCircumfix(
"pinocchio_model", system.name, "", TELEMETRY_FIELDNAME_DELIMITER);
std::string modelString = system.robot->pncModel_.saveToString();
Expand Down Expand Up @@ -2737,7 +2751,7 @@ namespace jiminy
// Create proxies for convenience
pinocchio::Model const & model = system.robot->pncModel_;
pinocchio::Data & data = system.robot->pncData_;
pinocchio::GeometryModel const & geomModel = system.robot->pncGeometryModel_;
pinocchio::GeometryModel const & geomModel = system.robot->collisionModel_;
pinocchio::GeometryData & geomData = *system.robot->pncGeometryData_;

// Update forward kinematics
Expand Down Expand Up @@ -2815,8 +2829,8 @@ namespace jiminy
// object simply by sampling points on the profile.

// Get the frame and joint indices
geomIndex_t const & geometryIdx = system.robot->pncGeometryModel_.collisionPairs[collisionPairIdx].first;
jointIndex_t const & parentJointIdx = system.robot->pncGeometryModel_.geometryObjects[geometryIdx].parentJoint;
geomIndex_t const & geometryIdx = system.robot->collisionModel_.collisionPairs[collisionPairIdx].first;
jointIndex_t const & parentJointIdx = system.robot->collisionModel_.geometryObjects[geometryIdx].parentJoint;

// Extract collision and distance results
hpp::fcl::CollisionResult const & collisionResult = system.robot->pncGeometryData_->collisionResults[collisionPairIdx];
Expand Down
Loading

0 comments on commit a7e3aa9

Please sign in to comment.