diff --git a/README.md b/README.md index 54c112e..df7d1fa 100644 --- a/README.md +++ b/README.md @@ -25,7 +25,7 @@ These libraries are distributed on PyPI, the packages are: * `dm_robotics-moma` * `dm_robotics-controllers` -Python versions 3.7, 3.8, 3.9 and 3.10 are supported. +Python versions 3.8, 3.9 and 3.10 are supported. ## Dependencies `MoMa`, `Manipulation` and `Controllers` depend on MuJoCo, the other packages do not. @@ -35,10 +35,9 @@ See the individual packages for more information on their dependencies. To build and test the libraries, run `build.sh`. This script assumes: -* MuJoCo is installed. * [`dm_control`](https://github.com/deepmind/dm_control) is installed. * cmake version >= 3.20.2 is installed. -* Python 3.7, 3.8, 3.9 or 3.10 and system headers are installed. +* Python 3.8, 3.9 or 3.10 and system headers are installed. * GCC version 9 or later is installed. * numpy is installed. diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index 4703607..80a6bff 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -15,13 +15,14 @@ cmake_minimum_required(VERSION 3.5) project(dm_robotics DESCRIPTION "DM Robotics" - VERSION 0.1 + VERSION 0.2 ) set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_EXTENSIONS OFF) set(CMAKE_POSITION_INDEPENDENT_CODE ON) +add_compile_options(-Wno-stringop-truncation) # To build a manylinux compatible wheel: # set DM_ROBOTICS_BUILD_WHEEL True @@ -127,6 +128,8 @@ if (DM_ROBOTICS_BUILD_dmr_support OR DM_ROBOTICS_BUILD_dmr_controllers OR DM_ROBOTICS_BUILD_dmr_controllers_python ) + set(ABSL_PROPAGATE_CXX_STD ON) + set(ABSL_BUILD_TESTING OFF) FindOrFetch( USE_SYSTEM_PACKAGE DM_ROBOTICS_USE_SYSTEM_absl @@ -137,7 +140,7 @@ if (DM_ROBOTICS_BUILD_dmr_support GIT_REPO https://github.com/abseil/abseil-cpp.git GIT_TAG - lts_2021_11_02 + c2435f8342c2d0ed8101cb43adfd605fdc52dca2 TARGETS absl::span absl::hash @@ -175,6 +178,25 @@ if (DM_ROBOTICS_BUILD_dmr_lsqp ) endif() +# MuJoco 3.0.0 +if (DM_ROBOTICS_MUJOCO_TAR) + message(STATUS "dm_robotics: MuJoCo TAR file specified at `${DM_ROBOTICS_MUJOCO_TAR}`.") +else() + message(STATUS "dm_robotics: MuJoCo TAR file not specified. Downloading MuJoCo....") + file(DOWNLOAD https://github.com/google-deepmind/mujoco/releases/download/3.0.0/mujoco-3.0.0-linux-x86_64.tar.gz mujoco.tar.gz) + set(DM_ROBOTICS_MUJOCO_TAR mujoco.tar.gz) +endif() +file(ARCHIVE_EXTRACT INPUT ${DM_ROBOTICS_MUJOCO_TAR} DESTINATION mujoco_bin) +message("Checking headers in ${CMAKE_CURRENT_BINARY_DIR}/mujoco_bin/mujoco-3.0.0/include/mujoco") +file(GLOB_RECURSE MUJOCO_HEADERS RELATIVE "${CMAKE_CURRENT_BINARY_DIR}" "${CMAKE_CURRENT_BINARY_DIR}/mujoco_bin/mujoco-3.0.0/include/mujoco/*.h") +message("Mujoco headers: ${MUJOCO_HEADERS}") +add_library(mujoco SHARED IMPORTED) +set_target_properties(mujoco PROPERTIES + IMPORTED_LOCATION ${CMAKE_CURRENT_BINARY_DIR}/mujoco_bin/mujoco-3.0.0/lib/libmujoco.so) +set_target_properties(mujoco PROPERTIES PUBLIC_HEADER "${MUJOCO_HEADERS}" + INTERFACE_INCLUDE_DIRECTORIES "${CMAKE_CURRENT_BINARY_DIR}/mujoco_bin/mujoco-3.0.0/include" +) + # osqp-cpp if (DM_ROBOTICS_BUILD_dmr_lsqp) # Deactivate OSQP tests. @@ -190,7 +212,7 @@ if (DM_ROBOTICS_BUILD_dmr_lsqp) GIT_REPO https://github.com/google/osqp-cpp.git GIT_TAG - 8cd904e2b49c24dd41d11f8c6e0adb113dd5e26c + 43433736334d6b515ea4b0247156fea9e56c0d3f TARGETS osqp-cpp ) diff --git a/cpp/controllers/lsqp/include/dm_robotics/controllers/lsqp/cartesian_6d_to_joint_velocity_mapper.h b/cpp/controllers/lsqp/include/dm_robotics/controllers/lsqp/cartesian_6d_to_joint_velocity_mapper.h index 79d82e7..0d446ee 100644 --- a/cpp/controllers/lsqp/include/dm_robotics/controllers/lsqp/cartesian_6d_to_joint_velocity_mapper.h +++ b/cpp/controllers/lsqp/include/dm_robotics/controllers/lsqp/cartesian_6d_to_joint_velocity_mapper.h @@ -76,9 +76,6 @@ class Cartesian6dToJointVelocityMapper { // outlive any Cartesian6dToJointVelocityMapper instances created with this // object. struct Parameters { - // Pointer to an MjLib object. - const MjLib* lib; - // Pointer to a MuJoCo model. const mjModel* model; diff --git a/cpp/controllers/lsqp/src/cartesian_6d_to_joint_velocity_mapper.cc b/cpp/controllers/lsqp/src/cartesian_6d_to_joint_velocity_mapper.cc index 667c669..82cabaa 100644 --- a/cpp/controllers/lsqp/src/cartesian_6d_to_joint_velocity_mapper.cc +++ b/cpp/controllers/lsqp/src/cartesian_6d_to_joint_velocity_mapper.cc @@ -39,6 +39,11 @@ namespace dm_robotics { namespace { +const MjLib* MjLibInitializer() { + static const MjLib* const lib = new MjLib("", 0); + return lib; +} + // Constructs an LsqpStackOfTasksSolver::Parameters object from // a Cartesian6dToJointVelocityMapper::Parameters object. LsqpStackOfTasksSolver::Parameters ToLsqpParams( @@ -77,7 +82,7 @@ LsqpStackOfTasksSolver::Parameters ToLsqpParams( Cartesian6dVelocityTask::Parameters ToCartesianVelocityParams( const Cartesian6dToJointVelocityMapper::Parameters& params) { Cartesian6dVelocityTask::Parameters output_params; - output_params.lib = params.lib; + output_params.lib = MjLibInitializer(); output_params.model = params.model; output_params.joint_ids = params.joint_ids; output_params.object_type = params.object_type; @@ -93,7 +98,7 @@ Cartesian6dVelocityDirectionTask::Parameters ToCartesianVelocityDirectionTaskParams( const Cartesian6dToJointVelocityMapper::Parameters& params) { Cartesian6dVelocityDirectionTask::Parameters output_params; - output_params.lib = params.lib; + output_params.lib = MjLibInitializer(); output_params.model = params.model; output_params.joint_ids = params.joint_ids; output_params.object_type = params.object_type; @@ -109,7 +114,7 @@ Cartesian6dVelocityDirectionConstraint::Parameters ToCartesianVelocityDirectionConstraintParams( const Cartesian6dToJointVelocityMapper::Parameters& params) { Cartesian6dVelocityDirectionConstraint::Parameters output_params; - output_params.lib = params.lib; + output_params.lib = MjLibInitializer(); output_params.model = params.model; output_params.joint_ids = params.joint_ids; output_params.object_type = params.object_type; @@ -124,7 +129,7 @@ ToCartesianVelocityDirectionConstraintParams( CollisionAvoidanceConstraint::Parameters ToCollisionAvoidanceParams( const Cartesian6dToJointVelocityMapper::Parameters& params) { CollisionAvoidanceConstraint::Parameters output_params; - output_params.lib = params.lib; + output_params.lib = MjLibInitializer(); output_params.model = params.model; output_params.use_minimum_distance_contacts_only = params.use_minimum_distance_contacts_only; @@ -157,7 +162,7 @@ CollisionAvoidanceConstraint::Parameters ToCollisionAvoidanceParams( // for most robot environments, as joint limits are such that parent-children // cannot collide. output_params.geom_pairs = CollisionPairsToGeomIdPairs( - *params.lib, *params.model, params.collision_pairs, false, false); + *MjLibInitializer(), *params.model, params.collision_pairs, false, false); return output_params; } @@ -286,10 +291,8 @@ absl::Status ValidateGeomGroup(const MjLib& lib, const mjModel& model, absl::Status Cartesian6dToJointVelocityMapper::ValidateParameters( const Parameters& params) { - if (params.lib == nullptr) { - return absl::InvalidArgumentError( - "ValidateParameters: `lib` cannot be null."); - } + const MjLib* lib = MjLibInitializer(); + if (params.model == nullptr) { return absl::InvalidArgumentError( "ValidateParameters: `model` cannot be null."); @@ -322,16 +325,15 @@ absl::Status Cartesian6dToJointVelocityMapper::ValidateParameters( return absl::InvalidArgumentError(absl::Substitute( "ValidateParameters: Objects of type [$0] are not supported. Only " "bodies, geoms, and sites are supported.", - params.lib->mju_type2Str(params.object_type))); + lib->mju_type2Str(params.object_type))); - bool is_object_found = - params.lib->mj_name2id(params.model, params.object_type, - params.object_name.c_str()) >= 0; + bool is_object_found = lib->mj_name2id(params.model, params.object_type, + params.object_name.c_str()) >= 0; if (!is_object_found) return absl::NotFoundError(absl::Substitute( "ValidateParameters: Could not find MuJoCo object with name [$0] and " "type [$1] in the provided model.", - params.object_name, params.lib->mju_type2Str(params.object_type))); + params.object_name, lib->mju_type2Str(params.object_type))); if (params.integration_timestep <= absl::ZeroDuration()) { return absl::InvalidArgumentError( @@ -362,9 +364,9 @@ absl::Status Cartesian6dToJointVelocityMapper::ValidateParameters( for (const auto& collision_pair : params.collision_pairs) { RETURN_IF_ERROR( - ValidateGeomGroup(*params.lib, *params.model, collision_pair.first)); + ValidateGeomGroup(*lib, *params.model, collision_pair.first)); RETURN_IF_ERROR( - ValidateGeomGroup(*params.lib, *params.model, collision_pair.second)); + ValidateGeomGroup(*lib, *params.model, collision_pair.second)); } if (params.cartesian_velocity_direction_task_weight < 0.0) { @@ -406,7 +408,7 @@ absl::Status Cartesian6dToJointVelocityMapper::ValidateParameters( Cartesian6dToJointVelocityMapper::Cartesian6dToJointVelocityMapper( const Parameters& params) - : lib_(*DieIfNull(params.lib)), + : lib_(*DieIfNull(MjLibInitializer())), model_(*DieIfNull(params.model)), data_(lib_.mj_makeData(&model_), lib_.mj_deleteData), joint_dof_ids_(JointIdsToDofIds(model_, params.joint_ids)), diff --git a/cpp/controllers/lsqp/tests/cartesian_6d_to_joint_velocity_mapper_test.cc b/cpp/controllers/lsqp/tests/cartesian_6d_to_joint_velocity_mapper_test.cc index d7cc2b1..4f7f0b8 100644 --- a/cpp/controllers/lsqp/tests/cartesian_6d_to_joint_velocity_mapper_test.cc +++ b/cpp/controllers/lsqp/tests/cartesian_6d_to_joint_velocity_mapper_test.cc @@ -55,7 +55,6 @@ TEST_P(Cartesian6dToJointVelocityMapperTest, // Instantiate mapper and solve once. Cartesian6dToJointVelocityMapper::Parameters params; - params.lib = mjlib_; params.model = model_.get(); params.joint_ids = kJointIds; params.object_type = kObjectType; @@ -114,7 +113,6 @@ TEST_P(Cartesian6dToJointVelocityMapperTest, // Shared parameters for optimization problem with and without nullspace // hierarchy. Cartesian6dToJointVelocityMapper::Parameters params; - params.lib = mjlib_; params.model = model_.get(); params.joint_ids = kJointIds; params.object_type = kObjectType; @@ -220,7 +218,6 @@ TEST_P(Cartesian6dToJointVelocityMapperTest, // Instantiate mapper. Cartesian6dToJointVelocityMapper::Parameters params; - params.lib = mjlib_; params.model = model_.get(); params.joint_ids = kJointIds; params.object_type = kObjectType; @@ -294,7 +291,6 @@ TEST_P(Cartesian6dToJointVelocityMapperTest, // Instantiate mapper and solve once. Cartesian6dToJointVelocityMapper::Parameters params; - params.lib = mjlib_; params.model = model_.get(); params.joint_ids = kJointIds; params.object_type = kObjectType; @@ -402,7 +398,6 @@ TEST_P(Cartesian6dToJointVelocityMapperTest, const double kNullspaceProjectionSlack = 0.1 * kSolutionTolerance; Cartesian6dToJointVelocityMapper::Parameters params; - params.lib = mjlib_; params.model = model_.get(); params.joint_ids = kJointIds; params.object_type = kObjectType; @@ -506,7 +501,6 @@ TEST_P( const double kNullspaceProjectionSlack = 0.1 * kSolutionTolerance; Cartesian6dToJointVelocityMapper::Parameters params; - params.lib = mjlib_; params.model = model_.get(); params.joint_ids = kJointIds; params.object_type = kObjectType; diff --git a/cpp/controllers_py/cartesian_6d_to_joint_velocity_mapper.cc b/cpp/controllers_py/cartesian_6d_to_joint_velocity_mapper.cc index 5d279d7..e29716c 100644 --- a/cpp/controllers_py/cartesian_6d_to_joint_velocity_mapper.cc +++ b/cpp/controllers_py/cartesian_6d_to_joint_velocity_mapper.cc @@ -22,6 +22,7 @@ #include "absl/strings/substitute.h" #include "absl/types/span.h" #include "dm_robotics/least_squares_qp/core/utils.h" +#include "dm_robotics/mujoco/mjlib.h" #include "pybind_utils.h" // controller #include "pybind11/chrono.h" // pybind #include "pybind11/pybind11.h" // pybind @@ -271,13 +272,6 @@ enabled. This overload should only be used if nullspace control is not enabled. using PybindGeomGroup = std::vector; using PybindCollisionPair = std::pair; -// A global singleton instance of MjLib that is loaded via dm_control's -// Python infrastructure. -const MjLib& MjLibInitializer() { - static const MjLib* const lib = internal::LoadMjLibFromDmControl(); - return *lib; -} - // Converts a non-ok `status` into a Python exception. // // Internal comment. @@ -291,11 +285,8 @@ void RaiseIfNotOk(const absl::Status& status) { // is alive. class PyCartesian6dToJointVelocityMapperParameters { public: - // The MjLib object is initialized at construction time and never exposed in - // Python. PyCartesian6dToJointVelocityMapperParameters() : py_model_(py::cast(nullptr)) { - params_.lib = &MjLibInitializer(); params_.model = nullptr; } diff --git a/cpp/controllers_py/pybind_utils.cc b/cpp/controllers_py/pybind_utils.cc index ae21f2a..cc1ff57 100644 --- a/cpp/controllers_py/pybind_utils.cc +++ b/cpp/controllers_py/pybind_utils.cc @@ -14,7 +14,6 @@ #include "pybind_utils.h" // controller -#include #include #include #include @@ -78,43 +77,6 @@ void RaiseRuntimeErrorWithMessage(absl::string_view message) { throw py::error_already_set(); } -const MjLib* LoadMjLibFromDmControlStatically() { - return new MjLib("", RTLD_NOW); -} - -const MjLib* LoadMjLibFromDmControlDynamically() { - // Get the path to the mujoco library. - const py::module mujoco(py::module::import("mujoco")); - - const py::list mujoco_path = mujoco.attr("__path__"); - if (mujoco_path.empty()) { - RaiseRuntimeErrorWithMessage("mujoco.__path__ is empty"); - return nullptr; - } - const auto path = py::str(mujoco_path[0]).cast(); - // Not all MuJoCo releases have __version__, they do have mj_versionString. - const auto version = mujoco.attr("mj_versionString")().cast(); - const std::string dso_path = path + "/libmujoco.so." + version; - - struct stat buffer; - if (stat(dso_path.c_str(), &buffer) != 0) { - RaiseRuntimeErrorWithMessage(absl::Substitute( - "LoadMjLibFromDmComtrol: Cannot access mujoco library file " - "$0, error: $1", - dso_path, strerror(errno))); - return nullptr; - } - py::print("Loading mujoco from " + dso_path); - - // Create the MjLib object by dlopen'ing the DSO. - return new MjLib(dso_path, RTLD_NOW); -} - -const MjLib* LoadMjLibFromDmControl() { - py::gil_scoped_acquire gil; - return LoadMjLibFromDmControlStatically(); // Copybara changes to dynamic. -} - // Helper function for getting an mjModel object from a py::handle. const mjModel* GetmjModelOrRaise(py::handle obj) { const std::string class_name = diff --git a/cpp/controllers_py/pybind_utils.h b/cpp/controllers_py/pybind_utils.h index fd6c458..d00baf0 100644 --- a/cpp/controllers_py/pybind_utils.h +++ b/cpp/controllers_py/pybind_utils.h @@ -24,18 +24,6 @@ namespace dm_robotics::internal { // Raises a `RuntimeError` exception in Python with the message `message`. void RaiseRuntimeErrorWithMessage(absl::string_view message); -// Loads a new MjLib object and activates it via dm_control's Python -// infrastructure. The user takes ownership of the allocated object. The -// recommended usage is to use this through the static-in-a-function pattern to -// instantiate a global singleton that is never deallocated. -// -// This is a helper-function for re-using the libmujoco.so and license file used -// by dm_control. It must only be used if dm_control is available; it will -// not work for binaries that are missing the symbols from the Python -// interpreter that come bundled with dm_control, causing the program to -// crash. -const MjLib* LoadMjLibFromDmControl(); - // Extracts an mjModel pointer from a Python handle to a dm_control `MjModel` // object. Raises a `RuntimeError` exception in Python if it fails to extract // an mjModel object from the handle. diff --git a/cpp/least_squares_qp/testing/CMakeLists.txt b/cpp/least_squares_qp/testing/CMakeLists.txt index d1754f7..cf18e78 100644 --- a/cpp/least_squares_qp/testing/CMakeLists.txt +++ b/cpp/least_squares_qp/testing/CMakeLists.txt @@ -19,6 +19,7 @@ set(HDRS ${CMAKE_CURRENT_SOURCE_DIR}/include/dm_robotics/least_squares_qp/testing/matchers.h ) add_library(dmr_lsqp_testing) +set_target_properties(dmr_lsqp_testing PROPERTIES LINKER_LANGUAGE CXX) target_sources(dmr_lsqp_testing PUBLIC ${HDRS}) target_include_directories(dmr_lsqp_core PUBLIC diff --git a/cpp/mujoco/CMakeLists.txt b/cpp/mujoco/CMakeLists.txt index 61c514f..a1e75b4 100644 --- a/cpp/mujoco/CMakeLists.txt +++ b/cpp/mujoco/CMakeLists.txt @@ -15,19 +15,18 @@ cmake_minimum_required(VERSION 3.5) project(dmr_mujoco DESCRIPTION "DM Robotics: MuJoCo utilities library" - VERSION 0.1 + VERSION 0.2 ) # Pick up the version of mujoco to use from the environment, # with an appropriate default if unset. set(MUJOCO_VERSION $ENV{MUJOCO_VERSION} CACHE STRING "Mujoco library version") if(NOT MUJOCO_VERSION) - set(MUJOCO_VERSION "2.3.1") + set(MUJOCO_VERSION "3.0.0") endif() message ("MUJOCO_VERSION: ${MUJOCO_VERSION}") # Generate defs.h from configuration with the MuJoCo constants. -set(DMR_MUJOCO_LIB_NOGL_PATH "$ENV{HOME}/.mujoco/mujoco-${MUJOCO_VERSION}/lib/libmujoco_nogl.so" CACHE STRING "Path to the MuJoCo shared library (`libmujoco_nogl.so`)") set(DMR_DMCONTROL_SUITE_PATH "$ENV{HOME}/.local/lib/python3.10/site-packages/dm_control/suite" CACHE STRING "Path to `dm_control.suite`") set(DMR_DMCONTROL_SUITE_HUMANOID_XML_PATH "${DMR_DMCONTROL_SUITE_PATH}/humanoid.xml") configure_file(${CMAKE_CURRENT_SOURCE_DIR}/cmake/defs.h.in @@ -52,7 +51,6 @@ target_include_directories(dmr_mujoco PUBLIC $ $ - $ ) target_link_libraries(dmr_mujoco PUBLIC @@ -63,10 +61,10 @@ target_link_libraries(dmr_mujoco absl::strings absl::status absl::statusor + mujoco PRIVATE dmr_support Eigen3::Eigen - ${CMAKE_DL_LIBS} ) diff --git a/cpp/mujoco/cmake/defs.h.in b/cpp/mujoco/cmake/defs.h.in index f62a554..8bffd28 100644 --- a/cpp/mujoco/cmake/defs.h.in +++ b/cpp/mujoco/cmake/defs.h.in @@ -1,16 +1,13 @@ #ifndef LEARNING_DEEPMIND_ROBOTICS_MUJOCO_DEFS_H_ #define LEARNING_DEEPMIND_ROBOTICS_MUJOCO_DEFS_H_ -// Paths to the dynamic libraries. Users must specify these constants through +// Users must specify this constant through // CMake if they wish to run the tests and examples provided with this library. -#cmakedefine DMR_MUJOCO_LIB_NOGL_PATH "@DMR_MUJOCO_LIB_NOGL_PATH@" #cmakedefine DMR_DMCONTROL_SUITE_HUMANOID_XML_PATH "@DMR_DMCONTROL_SUITE_HUMANOID_XML_PATH@" -inline constexpr char kMujocoLibNoGlPath[] = DMR_MUJOCO_LIB_NOGL_PATH; inline constexpr char kDmControlSuiteHumanoidXmlPath[] = DMR_DMCONTROL_SUITE_HUMANOID_XML_PATH; -#undef DMR_MUJOCO_LIB_NOGL_PATH #undef DMR_DMCONTROL_SUITE_HUMANOID_XML_PATH #endif // LEARNING_DEEPMIND_ROBOTICS_MUJOCO_DEFS_H_ diff --git a/cpp/mujoco/include/dm_robotics/mujoco/mjlib.h b/cpp/mujoco/include/dm_robotics/mujoco/mjlib.h index e0e49cd..245d01f 100644 --- a/cpp/mujoco/include/dm_robotics/mujoco/mjlib.h +++ b/cpp/mujoco/include/dm_robotics/mujoco/mjlib.h @@ -18,359 +18,293 @@ #include #include -// MuJoCo headers must be included in the same order as "mujoco.h". -#include //NOLINT -#include //NOLINT -#include //NOLINT -#include //NOLINT -#include //NOLINT +#include //NOLINT namespace dm_robotics { extern "C" { -using MjDefaultVFSFunc = void(mjVFS*); -using MjAddFileVFSFunc = int(mjVFS*, const char*, const char*); -using MjMakeEmptyFileVFSFunc = int(mjVFS*, const char*, int); -using MjFindFileVFSFunc = int(const mjVFS*, const char*); -using MjDeleteFileVFSFunc = int(mjVFS*, const char*); -using MjDeleteVFSFunc = void(mjVFS*); -using MjLoadXmlFunc = mjModel*(const char*, const mjVFS*, char*, int); -using MjSaveLastXMLFunc = int(const char*, const mjModel*, char*, int); -using MjFreeLastXMLFunc = void(); -using MjPrintSchemaFunc = int(const char*, char*, int, int, int); -using MjStepFunc = void(const mjModel*, mjData*); -using MjStep1Func = void(const mjModel*, mjData*); -using MjStep2Func = void(const mjModel*, mjData*); -using MjForwardFunc = void(const mjModel*, mjData*); -using MjInverseFunc = void(const mjModel*, mjData*); -using MjForwardSkipFunc = void(const mjModel*, mjData*, int, int); -using MjInverseSkipFunc = void(const mjModel*, mjData*, int, int); -using MjDefaultLROptFunc = void(mjLROpt*); -using MjDefaultSolRefImpFunc = void(mjtNum*, mjtNum*); -using MjDefaultOptionFunc = void(mjOption*); -using MjDefaultVisualFunc = void(mjVisual*); -using MjCopyModelFunc = mjModel*(mjModel*, const mjModel*); -using MjSaveModelFunc = void(const mjModel*, const char*, void*, int); -using MjLoadModelFunc = mjModel*(const char*, const mjVFS*); -using MjDeleteModelFunc = void(mjModel*); -using MjSizeModelFunc = int(const mjModel*); -using MjMakeDataFunc = mjData*(const mjModel*); -using MjCopyDataFunc = mjData*(mjData*, const mjModel*, const mjData*); -using MjResetDataFunc = void(const mjModel*, mjData*); -using MjResetDataDebugFunc = void(const mjModel*, mjData*, unsigned char); -using MjResetDataKeyframeFunc = void(const mjModel*, mjData*, int); -using MjDeleteDataFunc = void(mjData*); -using MjResetCallbacksFunc = void(); -using MjSetConstFunc = void(mjModel*, mjData*); -using MjSetLengthRangeFunc = int(mjModel*, mjData*, int, const mjLROpt*, char*, - int); -using MjPrintModelFunc = void(const mjModel*, const char*); -using MjPrintDataFunc = void(const mjModel*, mjData*, const char*); -using MjuPrintMatFunc = void(const mjtNum*, int, int); -using MjuPrintMatSparseFunc = void(const mjtNum*, int, const int*, const int*, - const int*); -using MjFwdPositionFunc = void(const mjModel*, mjData*); -using MjFwdVelocityFunc = void(const mjModel*, mjData*); -using MjFwdActuationFunc = void(const mjModel*, mjData*); -using MjFwdAccelerationFunc = void(const mjModel*, mjData*); -using MjFwdConstraintFunc = void(const mjModel*, mjData*); -using MjEulerFunc = void(const mjModel*, mjData*); -using MjRungeKuttaFunc = void(const mjModel*, mjData*, int); -using MjInvPositionFunc = void(const mjModel*, mjData*); -using MjInvVelocityFunc = void(const mjModel*, mjData*); -using MjInvConstraintFunc = void(const mjModel*, mjData*); -using MjCompareFwdInvFunc = void(const mjModel*, mjData*); -using MjSensorPosFunc = void(const mjModel*, mjData*); -using MjSensorVelFunc = void(const mjModel*, mjData*); -using MjSensorAccFunc = void(const mjModel*, mjData*); -using MjEnergyPosFunc = void(const mjModel*, mjData*); -using MjEnergyVelFunc = void(const mjModel*, mjData*); -using MjCheckPosFunc = void(const mjModel*, mjData*); -using MjCheckVelFunc = void(const mjModel*, mjData*); -using MjCheckAccFunc = void(const mjModel*, mjData*); -using MjKinematicsFunc = void(const mjModel*, mjData*); -using MjComPosFunc = void(const mjModel*, mjData*); -using MjCamlightFunc = void(const mjModel*, mjData*); -using MjTendonFunc = void(const mjModel*, mjData*); -using MjTransmissionFunc = void(const mjModel*, mjData*); -using MjCrbFunc = void(const mjModel*, mjData*); -using MjFactorMFunc = void(const mjModel*, mjData*); -using MjSolveMFunc = void(const mjModel*, mjData*, mjtNum*, const mjtNum*, int); -using MjSolveM2Func = void(const mjModel*, mjData*, mjtNum*, const mjtNum*, - int); -using MjComVelFunc = void(const mjModel*, mjData*); -using MjPassiveFunc = void(const mjModel*, mjData*); -using MjSubtreeVelFunc = void(const mjModel*, mjData*); -using MjRneFunc = void(const mjModel*, mjData*, int, mjtNum*); -using MjRnePostConstraintFunc = void(const mjModel*, mjData*); -using MjCollisionFunc = void(const mjModel*, mjData*); -using MjMakeConstraintFunc = void(const mjModel*, mjData*); -using MjProjectConstraintFunc = void(const mjModel*, mjData*); -using MjReferenceConstraintFunc = void(const mjModel*, mjData*); -using MjConstraintUpdateFunc = void(const mjModel*, mjData*, const mjtNum*, - mjtNum*, int); -using MjAddContactFunc = int(const mjModel*, mjData*, const mjContact*); -using MjIsPyramidalFunc = int(const mjModel*); -using MjIsSparseFunc = int(const mjModel*); -using MjIsDualFunc = int(const mjModel*); -using MjMulJacVecFunc = void(const mjModel*, mjData*, mjtNum*, const mjtNum*); -using MjMulJacTVecFunc = void(const mjModel*, mjData*, mjtNum*, const mjtNum*); -using MjJacFunc = void(const mjModel*, const mjData*, mjtNum*, mjtNum*, - const mjtNum[3], int); -using MjJacBodyFunc = void(const mjModel*, const mjData*, mjtNum*, mjtNum*, - int); -using MjJacBodyComFunc = void(const mjModel*, const mjData*, mjtNum*, mjtNum*, - int); -using MjJacGeomFunc = void(const mjModel*, const mjData*, mjtNum*, mjtNum*, - int); -using MjJacSiteFunc = void(const mjModel*, const mjData*, mjtNum*, mjtNum*, - int); -using MjJacPointAxisFunc = void(const mjModel*, mjData*, mjtNum*, mjtNum*, - const mjtNum[3], const mjtNum[3], int); -using MjName2IdFunc = int(const mjModel*, int, const char*); -using MjId2NameFunc = const char*(const mjModel*, int, int); -using MjFullMFunc = void(const mjModel*, mjtNum*, const mjtNum*); -using MjMulMFunc = void(const mjModel*, const mjData*, mjtNum*, const mjtNum*); -using MjMulM2Func = void(const mjModel*, const mjData*, mjtNum*, const mjtNum*); -using MjAddMFunc = void(const mjModel*, mjData*, mjtNum*, int*, int*, int*); -using MjApplyFTFunc = void(const mjModel*, mjData*, const mjtNum*, - const mjtNum*, const mjtNum*, int, mjtNum*); -using MjObjectVelocityFunc = void(const mjModel*, const mjData*, int, int, - mjtNum*, int); -using MjObjectAccelerationFunc = void(const mjModel*, const mjData*, int, int, - mjtNum*, int); -using MjContactForceFunc = void(const mjModel*, const mjData*, int, mjtNum*); -using MjDifferentiatePosFunc = void(const mjModel*, mjtNum*, mjtNum, - const mjtNum*, const mjtNum*); -using MjIntegratePosFunc = void(const mjModel*, mjtNum*, const mjtNum*, mjtNum); -using MjNormalizeQuatFunc = void(const mjModel*, mjtNum*); -using MjLocal2GlobalFunc = void(mjData*, mjtNum*, mjtNum*, const mjtNum*, - const mjtNum*, int, mjtByte); -using MjGetTotalmassFunc = mjtNum(const mjModel*); -using MjSetTotalmassFunc = void(mjModel*, mjtNum); -using MjVersionFunc = int(); -using MjRayFunc = mjtNum(const mjModel*, const mjData*, const mjtNum*, - const mjtNum*, const mjtByte*, mjtByte, int, int*); -using MjRayHfieldFunc = mjtNum(const mjModel*, const mjData*, int, - const mjtNum*, const mjtNum*); -using MjRayMeshFunc = mjtNum(const mjModel*, const mjData*, int, const mjtNum*, - const mjtNum*); -using MjuRayGeomFunc = mjtNum(const mjtNum*, const mjtNum*, const mjtNum*, - const mjtNum*, const mjtNum*, int); -using MjuRaySkinFunc = mjtNum(int, int, const int*, const float*, const mjtNum*, - const mjtNum*, int*); -using MjvDefaultCameraFunc = void(mjvCamera*); -using MjvDefaultPerturbFunc = void(mjvPerturb*); -using MjvRoom2ModelFunc = void(mjtNum*, mjtNum*, const mjtNum*, const mjtNum*, - const mjvScene*); -using MjvModel2RoomFunc = void(mjtNum*, mjtNum*, const mjtNum*, const mjtNum*, - const mjvScene*); -using MjvCameraInModelFunc = void(mjtNum*, mjtNum*, mjtNum*, const mjvScene*); -using MjvCameraInRoomFunc = void(mjtNum*, mjtNum*, mjtNum*, const mjvScene*); -using MjvFrustumHeightFunc = mjtNum(const mjvScene*); -using MjvAlignToCameraFunc = void(mjtNum*, const mjtNum*, const mjtNum*); -using MjvMoveCameraFunc = void(const mjModel*, int, mjtNum, mjtNum, - const mjvScene*, mjvCamera*); -using MjvMovePerturbFunc = void(const mjModel*, const mjData*, int, mjtNum, - mjtNum, const mjvScene*, mjvPerturb*); -using MjvMoveModelFunc = void(const mjModel*, int, mjtNum, mjtNum, - const mjtNum*, mjvScene*); -using MjvInitPerturbFunc = void(const mjModel*, const mjData*, const mjvScene*, - mjvPerturb*); -using MjvApplyPerturbPoseFunc = void(const mjModel*, mjData*, const mjvPerturb*, - int); -using MjvApplyPerturbForceFunc = void(const mjModel*, mjData*, - const mjvPerturb*); -using MjvAverageCameraFunc = mjvGLCamera(const mjvGLCamera*, - const mjvGLCamera*); -using MjvSelectFunc = int(const mjModel*, const mjData*, const mjvOption*, - mjtNum, mjtNum, mjtNum, const mjvScene*, mjtNum*, - int*, int*); -using MjvDefaultOptionFunc = void(mjvOption*); -using MjvDefaultFigureFunc = void(mjvFigure*); -using MjvInitGeomFunc = void(mjvGeom*, int, const mjtNum*, const mjtNum*, - const mjtNum*, const float*); -using MjvMakeConnectorFunc = void(mjvGeom*, int, mjtNum, mjtNum, mjtNum, mjtNum, - mjtNum, mjtNum, mjtNum); -using MjvDefaultSceneFunc = void(mjvScene*); -using MjvMakeSceneFunc = void(const mjModel*, mjvScene*, int); -using MjvFreeSceneFunc = void(mjvScene*); -using MjvUpdateSceneFunc = void(const mjModel*, mjData*, const mjvOption*, - const mjvPerturb*, mjvCamera*, int, mjvScene*); -using MjvAddGeomsFunc = void(const mjModel*, mjData*, const mjvOption*, - const mjvPerturb*, int, mjvScene*); -using MjvMakeLightsFunc = void(const mjModel*, mjData*, mjvScene*); -using MjvUpdateCameraFunc = void(const mjModel*, mjData*, mjvCamera*, - mjvScene*); -using MjvUpdateSkinFunc = void(const mjModel*, mjData*, mjvScene*); -using MjrDefaultContextFunc = void(mjrContext*); -using MjrMakeContextFunc = void(const mjModel*, mjrContext*, int); -using MjrChangeFontFunc = void(int, mjrContext*); -using MjrAddAuxFunc = void(int, int, int, int, mjrContext*); -using MjrFreeContextFunc = void(mjrContext*); -using MjrUploadTextureFunc = void(const mjModel*, const mjrContext*, int); -using MjrUploadMeshFunc = void(const mjModel*, const mjrContext*, int); -using MjrUploadHFieldFunc = void(const mjModel*, const mjrContext*, int); -using MjrRestoreBufferFunc = void(const mjrContext*); -using MjrSetBufferFunc = void(int, mjrContext*); -using MjrReadPixelsFunc = void(unsigned char*, float*, mjrRect, - const mjrContext*); -using MjrDrawPixelsFunc = void(const unsigned char*, const float*, mjrRect, - const mjrContext*); -using MjrBlitBufferFunc = void(mjrRect, mjrRect, int, int, const mjrContext*); -using MjrSetAuxFunc = void(int, const mjrContext*); -using MjrBlitAuxFunc = void(int, mjrRect, int, int, const mjrContext*); -using MjrTextFunc = void(int, const char*, const mjrContext*, float, float, - float, float, float); -using MjrOverlayFunc = void(int, int, mjrRect, const char*, const char*, - const mjrContext*); -using MjrMaxViewportFunc = mjrRect(const mjrContext*); -using MjrRectangleFunc = void(mjrRect, float, float, float, float); -using MjrFigureFunc = void(mjrRect, mjvFigure*, const mjrContext*); -using MjrRenderFunc = void(mjrRect, mjvScene*, const mjrContext*); -using MjrFinishFunc = void(); -using MjrGetErrorFunc = int(); -using MjrFindRectFunc = int(int, int, int, const mjrRect*); -using MjuiThemeSpacingFunc = mjuiThemeSpacing(int); -using MjuiThemeColorFunc = mjuiThemeColor(int); -using MjuiAddFunc = void(mjUI*, const mjuiDef*); -using MjuiResizeFunc = void(mjUI*, const mjrContext*); -using MjuiUpdateFunc = void(int, int, const mjUI*, const mjuiState*, - const mjrContext*); -using MjuiEventFunc = mjuiItem*(mjUI*, mjuiState*, const mjrContext*); -using MjuiRenderFunc = void(mjUI*, const mjuiState*, const mjrContext*); -using MjuErrorFunc = void(const char*); -using MjuErrorIFunc = void(const char*, int); -using MjuErrorSFunc = void(const char*, const char*); -using MjuWarningFunc = void(const char*); -using MjuWarningIFunc = void(const char*, int); -using MjuWarningSFunc = void(const char*, const char*); -using MjuClearHandlersFunc = void(); -using MjuMallocFunc = void(int); -using MjuFreeFunc = void(void*); -using MjWarningFunc = void(mjData*, int, int); -using MjuWriteLogFunc = void(const char*, const char*); -using MjuZero3Func = void(mjtNum[3]); -using MjuCopy3Func = void(mjtNum[3], const mjtNum[3]); -using MjuScl3Func = void(mjtNum[3], const mjtNum[3], mjtNum); -using MjuAdd3Func = void(mjtNum[3], const mjtNum[3], const mjtNum[3]); -using MjuSub3Func = void(mjtNum[3], const mjtNum[3], const mjtNum[3]); -using MjuAddTo3Func = void(mjtNum[3], const mjtNum[3]); -using MjuSubFrom3Func = void(mjtNum[3], const mjtNum[3]); -using MjuAddToScl3Func = void(mjtNum[3], const mjtNum[3], mjtNum); -using MjuAddScl3Func = void(mjtNum[3], const mjtNum[3], const mjtNum[3], - mjtNum); -using MjuNormalize3Func = mjtNum(mjtNum[3]); -using MjuNorm3Func = mjtNum(const mjtNum[3]); -using MjuDot3Func = mjtNum(const mjtNum[3], const mjtNum[3]); -using MjuDist3Func = mjtNum(const mjtNum[3], const mjtNum[3]); -using MjuRotVecMatFunc = void(mjtNum[3], const mjtNum[3], const mjtNum[9]); -using MjuRotVecMatTFunc = void(mjtNum[3], const mjtNum[3], const mjtNum[9]); -using MjuCrossFunc = void(mjtNum[3], const mjtNum[3], const mjtNum[3]); -using MjuZero4Func = void(mjtNum[4]); -using MjuUnit4Func = void(mjtNum[4]); -using MjuCopy4Func = void(mjtNum[4], const mjtNum[4]); -using MjuNormalize4Func = mjtNum(mjtNum[4]); -using MjuZeroFunc = void(mjtNum*, int); -using MjuCopyFunc = void(mjtNum*, const mjtNum*, int); -using MjuSumFunc = mjtNum(const mjtNum*, int); -using MjuL1Func = mjtNum(const mjtNum*, int); -using MjuSclFunc = void(mjtNum*, const mjtNum*, mjtNum, int); -using MjuAddFunc = void(mjtNum*, const mjtNum*, const mjtNum*, int); -using MjuSubFunc = void(mjtNum*, const mjtNum*, const mjtNum*, int); -using MjuAddToFunc = void(mjtNum*, const mjtNum*, int); -using MjuSubFromFunc = void(mjtNum*, const mjtNum*, int); -using MjuAddToSclFunc = void(mjtNum*, const mjtNum*, mjtNum, int); -using MjuAddSclFunc = void(mjtNum*, const mjtNum*, const mjtNum*, mjtNum, int); -using MjuNormalizeFunc = mjtNum(mjtNum*, int); -using MjuNormFunc = mjtNum(const mjtNum*, int); -using MjuDotFunc = mjtNum(const mjtNum*, const mjtNum*, const int); -using MjuMulMatVecFunc = void(mjtNum*, const mjtNum*, const mjtNum*, int, int); -using MjuMulMatTVecFunc = void(mjtNum*, const mjtNum*, const mjtNum*, int, int); -using MjuTransposeFunc = void(mjtNum*, const mjtNum*, int, int); -using MjuMulMatMatFunc = void(mjtNum*, const mjtNum*, const mjtNum*, int, int, - int); -using MjuMulMatMatTFunc = void(mjtNum*, const mjtNum*, const mjtNum*, int, int, - int); -using MjuMulMatTMatFunc = void(mjtNum*, const mjtNum*, const mjtNum*, int, int, - int); -using MjuSqrMatTDFunc = void(mjtNum*, const mjtNum*, const mjtNum*, int, int); -using MjuTransformSpatialFunc = void(mjtNum[6], const mjtNum[6], int, - const mjtNum[3], const mjtNum[3], - const mjtNum[9]); -using MjuRotVecQuatFunc = void(mjtNum[3], const mjtNum[3], const mjtNum[4]); -using MjuNegQuatFunc = void(mjtNum[4], const mjtNum[4]); -using MjuMulQuatFunc = void(mjtNum[4], const mjtNum[4], const mjtNum[4]); -using MjuMulQuatAxisFunc = void(mjtNum[4], const mjtNum[4], const mjtNum[3]); -using MjuAxisAngle2QuatFunc = void(mjtNum[4], const mjtNum[3], mjtNum); -using MjuQuat2VelFunc = void(mjtNum[3], const mjtNum[4], mjtNum); -using MjuSubQuatFunc = void(mjtNum[3], const mjtNum[4], const mjtNum[4]); -using MjuQuat2MatFunc = void(mjtNum[9], const mjtNum[4]); -using MjuMat2QuatFunc = void(mjtNum[4], const mjtNum[9]); -using MjuDerivQuatFunc = void(mjtNum[4], const mjtNum[4], const mjtNum[3]); -using MjuQuatIntegrateFunc = void(mjtNum[4], const mjtNum[3], mjtNum); -using MjuQuatZ2VecFunc = void(mjtNum[4], const mjtNum[3]); -using MjuMulPoseFunc = void(mjtNum[3], mjtNum[4], const mjtNum[3], - const mjtNum[4], const mjtNum[3], const mjtNum[4]); -using MjuNegPoseFunc = void(mjtNum[3], mjtNum[4], const mjtNum[3], - const mjtNum[4]); -using MjuTrnVecPoseFunc = void(mjtNum[3], const mjtNum[3], const mjtNum[4], - const mjtNum[3]); -using MjuCholFactorFunc = int(mjtNum*, int, mjtNum); -using MjuCholSolveFunc = void(mjtNum*, const mjtNum*, const mjtNum*, int); -using MjuCholUpdateFunc = int(mjtNum*, mjtNum*, int, int); -using MjuEig3Func = int(mjtNum*, mjtNum*, mjtNum*, const mjtNum*); -using MjuMuscleGainFunc = mjtNum(mjtNum, mjtNum, const mjtNum[2], mjtNum, - const mjtNum[9]); -using MjuMuscleBiasFunc = mjtNum(mjtNum, const mjtNum[2], mjtNum, - const mjtNum[9]); -using MjuMuscleDynamicsFunc = mjtNum(mjtNum, mjtNum, const mjtNum[2]); -using MjuEncodePyramidFunc = void(mjtNum*, const mjtNum*, const mjtNum*, int); -using MjuDecodePyramidFunc = void(mjtNum*, const mjtNum*, const mjtNum*, int); -using MjuSpringDamperFunc = mjtNum(mjtNum, mjtNum, mjtNum, mjtNum, mjtNum); -using MjuMinFunc = mjtNum(mjtNum, mjtNum); -using MjuMaxFunc = mjtNum(mjtNum, mjtNum); -using MjuSignFunc = mjtNum(mjtNum); -using MjuRoundFunc = int(mjtNum); -using MjuType2StrFunc = const char*(int); -using MjuStr2TypeFunc = int(const char*); -using MjuWarningTextFunc = const char*(int, int); -using MjuIsBadFunc = int(mjtNum); -using MjuIsZeroFunc = int(mjtNum*, int); -using MjuStandardNormalFunc = mjtNum(mjtNum*); -using MjuF2NFunc = void(mjtNum*, const float*, int); -using MjuN2FFunc = void(float*, const mjtNum*, int); -using MjuD2NFunc = void(mjtNum*, const double*, int); -using MjuN2DFunc = void(double*, const mjtNum*, int); -using MjuInsertionSortFunc = void(mjtNum*, int); -using MjuHaltonFunc = mjtNum(int, int); -using MjuStrncpyFunc = char*(char*, const char*, int); +using MjDefaultVFSFunc = decltype(mj_defaultVFS); +using MjAddFileVFSFunc = decltype(mj_addFileVFS); +using MjMakeEmptyFileVFSFunc = decltype(mj_makeEmptyFileVFS); +using MjFindFileVFSFunc = decltype(mj_findFileVFS); +using MjDeleteFileVFSFunc = decltype(mj_deleteFileVFS); +using MjDeleteVFSFunc = decltype(mj_deleteVFS); +using MjLoadXmlFunc = decltype(mj_loadXML); +using MjSaveLastXMLFunc = decltype(mj_saveLastXML); +using MjFreeLastXMLFunc = decltype(mj_freeLastXML); +using MjPrintSchemaFunc = decltype(mj_printSchema); +using MjStepFunc = decltype(mj_step); +using MjStep1Func = decltype(mj_step1); +using MjStep2Func = decltype(mj_step2); +using MjForwardFunc = decltype(mj_forward); +using MjInverseFunc = decltype(mj_inverse); +using MjForwardSkipFunc = decltype(mj_forwardSkip); +using MjInverseSkipFunc = decltype(mj_inverseSkip); +using MjDefaultLROptFunc = decltype(mj_defaultLROpt); +using MjDefaultSolRefImpFunc = decltype(mj_defaultSolRefImp); +using MjDefaultOptionFunc = decltype(mj_defaultOption); +using MjDefaultVisualFunc = decltype(mj_defaultVisual); +using MjCopyModelFunc = decltype(mj_copyModel); +using MjSaveModelFunc = decltype(mj_saveModel); +using MjLoadModelFunc = decltype(mj_loadModel); +using MjDeleteModelFunc = decltype(mj_deleteModel); +using MjSizeModelFunc = decltype(mj_sizeModel); +using MjMakeDataFunc = decltype(mj_makeData); +using MjCopyDataFunc = decltype(mj_copyData); +using MjResetDataFunc = decltype(mj_resetData); +using MjResetDataDebugFunc = decltype(mj_resetDataDebug); +using MjResetDataKeyframeFunc = decltype(mj_resetDataKeyframe); +using MjDeleteDataFunc = decltype(mj_deleteData); +using MjResetCallbacksFunc = decltype(mj_resetCallbacks); +using MjSetConstFunc = decltype(mj_setConst); +using MjSetLengthRangeFunc = decltype(mj_setLengthRange); +using MjPrintModelFunc = decltype(mj_printModel); +using MjPrintDataFunc = decltype(mj_printData); +using MjuPrintMatFunc = decltype(mju_printMat); +using MjuPrintMatSparseFunc = decltype(mju_printMatSparse); +using MjFwdPositionFunc = decltype(mj_fwdPosition); +using MjFwdVelocityFunc = decltype(mj_fwdVelocity); +using MjFwdActuationFunc = decltype(mj_fwdActuation); +using MjFwdAccelerationFunc = decltype(mj_fwdAcceleration); +using MjFwdConstraintFunc = decltype(mj_fwdConstraint); +using MjEulerFunc = decltype(mj_Euler); +using MjRungeKuttaFunc = decltype(mj_RungeKutta); +using MjInvPositionFunc = decltype(mj_invPosition); +using MjInvVelocityFunc = decltype(mj_invVelocity); +using MjInvConstraintFunc = decltype(mj_invConstraint); +using MjCompareFwdInvFunc = decltype(mj_compareFwdInv); +using MjSensorPosFunc = decltype(mj_sensorPos); +using MjSensorVelFunc = decltype(mj_sensorVel); +using MjSensorAccFunc = decltype(mj_sensorAcc); +using MjEnergyPosFunc = decltype(mj_energyPos); +using MjEnergyVelFunc = decltype(mj_energyVel); +using MjCheckPosFunc = decltype(mj_checkPos); +using MjCheckVelFunc = decltype(mj_checkVel); +using MjCheckAccFunc = decltype(mj_checkAcc); +using MjKinematicsFunc = decltype(mj_kinematics); +using MjComPosFunc = decltype(mj_comPos); +using MjCamlightFunc = decltype(mj_camlight); +using MjTendonFunc = decltype(mj_tendon); +using MjTransmissionFunc = decltype(mj_transmission); +using MjCrbFunc = decltype(mj_crb); +using MjFactorMFunc = decltype(mj_factorM); +using MjSolveMFunc = decltype(mj_solveM); +using MjSolveM2Func = decltype(mj_solveM2); +using MjComVelFunc = decltype(mj_comVel); +using MjPassiveFunc = decltype(mj_passive); +using MjSubtreeVelFunc = decltype(mj_subtreeVel); +using MjRneFunc = decltype(mj_rne); +using MjRnePostConstraintFunc = decltype(mj_rnePostConstraint); +using MjCollisionFunc = decltype(mj_collision); +using MjMakeConstraintFunc = decltype(mj_makeConstraint); +using MjProjectConstraintFunc = decltype(mj_projectConstraint); +using MjReferenceConstraintFunc = decltype(mj_referenceConstraint); +using MjConstraintUpdateFunc = decltype(mj_constraintUpdate); +using MjAddContactFunc = decltype(mj_addContact); +using MjIsPyramidalFunc = decltype(mj_isPyramidal); +using MjIsSparseFunc = decltype(mj_isSparse); +using MjIsDualFunc = decltype(mj_isDual); +using MjMulJacVecFunc = decltype(mj_mulJacVec); +using MjMulJacTVecFunc = decltype(mj_mulJacTVec); +using MjJacFunc = decltype(mj_jac); +using MjJacBodyFunc = decltype(mj_jacBody); +using MjJacBodyComFunc = decltype(mj_jacBodyCom); +using MjJacGeomFunc = decltype(mj_jacGeom); +using MjJacSiteFunc = decltype(mj_jacSite); +using MjJacPointAxisFunc = decltype(mj_jacPointAxis); +using MjName2IdFunc = decltype(mj_name2id); +using MjId2NameFunc = decltype(mj_id2name); +using MjFullMFunc = decltype(mj_fullM); +using MjMulMFunc = decltype(mj_mulM); +using MjMulM2Func = decltype(mj_mulM2); +using MjAddMFunc = decltype(mj_addM); +using MjApplyFTFunc = decltype(mj_applyFT); +using MjObjectVelocityFunc = decltype(mj_objectVelocity); +using MjObjectAccelerationFunc = decltype(mj_objectAcceleration); +using MjContactForceFunc = decltype(mj_contactForce); +using MjDifferentiatePosFunc = decltype(mj_differentiatePos); +using MjIntegratePosFunc = decltype(mj_integratePos); +using MjNormalizeQuatFunc = decltype(mj_normalizeQuat); +using MjLocal2GlobalFunc = decltype(mj_local2Global); +using MjGetTotalmassFunc = decltype(mj_getTotalmass); +using MjSetTotalmassFunc = decltype(mj_setTotalmass); +using MjVersionFunc = decltype(mj_version); +using MjRayFunc = decltype(mj_ray); +using MjRayHfieldFunc = decltype(mj_rayHfield); +using MjRayMeshFunc = decltype(mj_rayMesh); +using MjuRayGeomFunc = decltype(mju_rayGeom); +using MjuRaySkinFunc = decltype(mju_raySkin); +using MjvDefaultCameraFunc = decltype(mjv_defaultCamera); +using MjvDefaultPerturbFunc = decltype(mjv_defaultPerturb); +using MjvRoom2ModelFunc = decltype(mjv_room2model); +using MjvModel2RoomFunc = decltype(mjv_model2room); +using MjvCameraInModelFunc = decltype(mjv_cameraInModel); +using MjvCameraInRoomFunc = decltype(mjv_cameraInRoom); +using MjvFrustumHeightFunc = decltype(mjv_frustumHeight); +using MjvAlignToCameraFunc = decltype(mjv_alignToCamera); +using MjvMoveCameraFunc = decltype(mjv_moveCamera); +using MjvMovePerturbFunc = decltype(mjv_movePerturb); +using MjvMoveModelFunc = decltype(mjv_moveModel); +using MjvInitPerturbFunc = decltype(mjv_initPerturb); +using MjvApplyPerturbPoseFunc = decltype(mjv_applyPerturbPose); +using MjvApplyPerturbForceFunc = decltype(mjv_applyPerturbForce); +using MjvAverageCameraFunc = decltype(mjv_averageCamera); +using MjvSelectFunc = decltype(mjv_select); +using MjvDefaultOptionFunc = decltype(mjv_defaultOption); +using MjvDefaultFigureFunc = decltype(mjv_defaultFigure); +using MjvInitGeomFunc = decltype(mjv_initGeom); +using MjvMakeConnectorFunc = decltype(mjv_makeConnector); +using MjvDefaultSceneFunc = decltype(mjv_defaultScene); +using MjvMakeSceneFunc = decltype(mjv_makeScene); +using MjvFreeSceneFunc = decltype(mjv_freeScene); +using MjvUpdateSceneFunc = decltype(mjv_updateScene); +using MjvAddGeomsFunc = decltype(mjv_addGeoms); +using MjvMakeLightsFunc = decltype(mjv_makeLights); +using MjvUpdateCameraFunc = decltype(mjv_updateCamera); +using MjvUpdateSkinFunc = decltype(mjv_updateSkin); +using MjrDefaultContextFunc = decltype(mjr_defaultContext); +using MjrMakeContextFunc = decltype(mjr_makeContext); +using MjrChangeFontFunc = decltype(mjr_changeFont); +using MjrAddAuxFunc = decltype(mjr_addAux); +using MjrFreeContextFunc = decltype(mjr_freeContext); +using MjrUploadTextureFunc = decltype(mjr_uploadTexture); +using MjrUploadMeshFunc = decltype(mjr_uploadMesh); +using MjrUploadHFieldFunc = decltype(mjr_uploadHField); +using MjrRestoreBufferFunc = decltype(mjr_restoreBuffer); +using MjrSetBufferFunc = decltype(mjr_setBuffer); +using MjrReadPixelsFunc = decltype(mjr_readPixels); +using MjrDrawPixelsFunc = decltype(mjr_drawPixels); +using MjrBlitBufferFunc = decltype(mjr_blitBuffer); +using MjrSetAuxFunc = decltype(mjr_setAux); +using MjrBlitAuxFunc = decltype(mjr_blitAux); +using MjrTextFunc = decltype(mjr_text); +using MjrOverlayFunc = decltype(mjr_overlay); +using MjrMaxViewportFunc = decltype(mjr_maxViewport); +using MjrRectangleFunc = decltype(mjr_rectangle); +using MjrFigureFunc = decltype(mjr_figure); +using MjrRenderFunc = decltype(mjr_render); +using MjrFinishFunc = decltype(mjr_finish); +using MjrGetErrorFunc = decltype(mjr_getError); +using MjrFindRectFunc = decltype(mjr_findRect); +using MjuiThemeSpacingFunc = decltype(mjui_themeSpacing); +using MjuiThemeColorFunc = decltype(mjui_themeColor); +using MjuiAddFunc = decltype(mjui_add); +using MjuiResizeFunc = decltype(mjui_resize); +using MjuiUpdateFunc = decltype(mjui_update); +using MjuiEventFunc = decltype(mjui_event); +using MjuiRenderFunc = decltype(mjui_render); +using MjuErrorFunc = decltype(mju_error); +using MjuErrorIFunc = decltype(mju_error_i); +using MjuErrorSFunc = decltype(mju_error_s); +using MjuWarningFunc = decltype(mju_warning); +using MjuWarningIFunc = decltype(mju_warning_i); +using MjuWarningSFunc = decltype(mju_warning_s); +using MjuClearHandlersFunc = decltype(mju_clearHandlers); +using MjuMallocFunc = decltype(mju_malloc); +using MjuFreeFunc = decltype(mju_free); +using MjWarningFunc = decltype(mj_warning); +using MjuWriteLogFunc = decltype(mju_writeLog); +using MjuZero3Func = decltype(mju_zero3); +using MjuCopy3Func = decltype(mju_copy3); +using MjuScl3Func = decltype(mju_scl3); +using MjuAdd3Func = decltype(mju_add3); +using MjuSub3Func = decltype(mju_sub3); +using MjuAddTo3Func = decltype(mju_addTo3); +using MjuSubFrom3Func = decltype(mju_subFrom3); +using MjuAddToScl3Func = decltype(mju_addToScl3); +using MjuAddScl3Func = decltype(mju_addScl3); +using MjuNormalize3Func = decltype(mju_normalize3); +using MjuNorm3Func = decltype(mju_norm3); +using MjuDot3Func = decltype(mju_dot3); +using MjuDist3Func = decltype(mju_dist3); +using MjuRotVecMatFunc = decltype(mju_rotVecMat); +using MjuRotVecMatTFunc = decltype(mju_rotVecMatT); +using MjuCrossFunc = decltype(mju_cross); +using MjuZero4Func = decltype(mju_zero4); +using MjuUnit4Func = decltype(mju_unit4); +using MjuCopy4Func = decltype(mju_copy4); +using MjuNormalize4Func = decltype(mju_normalize4); +using MjuZeroFunc = decltype(mju_zero); +using MjuCopyFunc = decltype(mju_copy); +using MjuSumFunc = decltype(mju_sum); +using MjuL1Func = decltype(mju_L1); +using MjuSclFunc = decltype(mju_scl); +using MjuAddFunc = decltype(mju_add); +using MjuSubFunc = decltype(mju_sub); +using MjuAddToFunc = decltype(mju_addTo); +using MjuSubFromFunc = decltype(mju_subFrom); +using MjuAddToSclFunc = decltype(mju_addToScl); +using MjuAddSclFunc = decltype(mju_addScl); +using MjuNormalizeFunc = decltype(mju_normalize); +using MjuNormFunc = decltype(mju_norm); +using MjuDotFunc = decltype(mju_dot); +using MjuMulMatVecFunc = decltype(mju_mulMatVec); +using MjuMulMatTVecFunc = decltype(mju_mulMatTVec); +using MjuTransposeFunc = decltype(mju_transpose); +using MjuMulMatMatFunc = decltype(mju_mulMatMat); +using MjuMulMatMatTFunc = decltype(mju_mulMatMatT); +using MjuMulMatTMatFunc = decltype(mju_mulMatTMat); +using MjuSqrMatTDFunc = decltype(mju_sqrMatTD); +using MjuTransformSpatialFunc = decltype(mju_transformSpatial); +using MjuRotVecQuatFunc = decltype(mju_rotVecQuat); +using MjuNegQuatFunc = decltype(mju_negQuat); +using MjuMulQuatFunc = decltype(mju_mulQuat); +using MjuMulQuatAxisFunc = decltype(mju_mulQuatAxis); +using MjuAxisAngle2QuatFunc = decltype(mju_axisAngle2Quat); +using MjuQuat2VelFunc = decltype(mju_quat2Vel); +using MjuSubQuatFunc = decltype(mju_subQuat); +using MjuQuat2MatFunc = decltype(mju_quat2Mat); +using MjuMat2QuatFunc = decltype(mju_mat2Quat); +using MjuDerivQuatFunc = decltype(mju_derivQuat); +using MjuQuatIntegrateFunc = decltype(mju_quatIntegrate); +using MjuQuatZ2VecFunc = decltype(mju_quatZ2Vec); +using MjuMulPoseFunc = decltype(mju_mulPose); +using MjuNegPoseFunc = decltype(mju_negPose); +using MjuTrnVecPoseFunc = decltype(mju_trnVecPose); +using MjuCholFactorFunc = decltype(mju_cholFactor); +using MjuCholSolveFunc = decltype(mju_cholSolve); +using MjuCholUpdateFunc = decltype(mju_cholUpdate); +using MjuEig3Func = decltype(mju_eig3); +using MjuMuscleGainFunc = decltype(mju_muscleGain); +using MjuMuscleBiasFunc = decltype(mju_muscleBias); +using MjuMuscleDynamicsFunc = decltype(mju_muscleDynamics); +using MjuEncodePyramidFunc = decltype(mju_encodePyramid); +using MjuDecodePyramidFunc = decltype(mju_decodePyramid); +using MjuSpringDamperFunc = decltype(mju_springDamper); +using MjuMinFunc = decltype(mju_min); +using MjuMaxFunc = decltype(mju_max); +using MjuSignFunc = decltype(mju_sign); +using MjuRoundFunc = decltype(mju_round); +using MjuType2StrFunc = decltype(mju_type2Str); +using MjuStr2TypeFunc = decltype(mju_str2Type); +using MjuWarningTextFunc = decltype(mju_warningText); +using MjuIsBadFunc = decltype(mju_isBad); +using MjuIsZeroFunc = decltype(mju_isZero); +using MjuStandardNormalFunc = decltype(mju_standardNormal); +using MjuF2NFunc = decltype(mju_f2n); +using MjuN2FFunc = decltype(mju_n2f); +using MjuD2NFunc = decltype(mju_d2n); +using MjuN2DFunc = decltype(mju_n2d); +using MjuInsertionSortFunc = decltype(mju_insertionSort); +using MjuHaltonFunc = decltype(mju_Halton); +using MjuStrncpyFunc = decltype(mju_strncpy); } // extern "C" // A struct containing pointers to MuJoCo public API functions. // -// This is provided for use with binaries that cannot depend on `libmujoco.so` -// at link time, for example when MuJoCo is loaded through Python's `ctypes` -// machinery. This struct resolves MuJoCo symbols using `dlsym` in its -// constructor, and exposes public member function pointers with the same -// names and signatures as in `mujoco.h`. +// This is in the process of being phased out, but is necessary due to legacy +// code. class MjLib { - private: - // Note that pimpl_ needs to be initialized before any function pointers, as - // it holds the handle to the MuJoCo library. - struct Impl; - std::unique_ptr pimpl_; - public: - // Initializes an MjLib object by loading the MuJoCo dynamic library. + // Initializes an MjLib object. // // Args: - // libmujoco_path: The path to the MuJoCo dynamic library. - // dlopen_flags: The flags variable to be passed to `dlopen`. See the man - // page for `dlopen(3)` for the list of valid flags (also available at - // http://man7.org/linux/man-pages/man3/dlopen.3.html). + // libmujoco_path: Ignored, function signature is only for backwards + // compatibility purposes. + // dlopen_flags: Ignored, function signature is only for backwards + // compatibility purposes. MjLib(const std::string& libmujoco_path, int dlopen_flags); ~MjLib(); @@ -642,7 +576,7 @@ class MjLib { // References to global callback function pointers. mjfGeneric& mjcb_passive; // NOLINT mjfGeneric& mjcb_control; // NOLINT - mjfGeneric& mjcb_contactfilter; // NOLINT + mjfConFilt& mjcb_contactfilter; // NOLINT mjfSensor& mjcb_sensor; // NOLINT mjfTime& mjcb_time; // NOLINT mjfAct& mjcb_act_dyn; // NOLINT diff --git a/cpp/mujoco/src/mjlib.cc b/cpp/mujoco/src/mjlib.cc index 8677483..17d805d 100644 --- a/cpp/mujoco/src/mjlib.cc +++ b/cpp/mujoco/src/mjlib.cc @@ -14,346 +14,292 @@ #include "dm_robotics/mujoco/mjlib.h" -#include - -#include #include -#include "dm_robotics/support/logging.h" -#include "absl/memory/memory.h" +#include //NOLINT namespace dm_robotics { -namespace { - -// An RAII wrapper for the POSIX dlopen/dlclose API. -struct LibMujocoHandleDeleter { - void operator()(void* handle) const { dlclose(handle); } -}; -using LibMujocoHandle = std::unique_ptr; - -LibMujocoHandle OpenImpl(const char *path, int dlopen_flags) { - dlerror(); // Clear error state before calling dlopen. - void* handle = dlopen(path, dlopen_flags); - CHECK_NE(handle, nullptr) << "dlopen '" << path << "' failed: " << dlerror(); - - // Ensure we close the library with dlclose: - LibMujocoHandle handle_with_close(handle); - - // validate the library: - dlerror(); // Clear error state before calling dlsym. - if (!dlsym(handle, "mj_version")) { - LOG(FATAL) << "MuJoCo symbols not present: " << dlerror(); - } - - return handle_with_close; -} - -LibMujocoHandle DlOpen(const std::string& path, int dlopen_flags) { - return OpenImpl(nullptr, RTLD_NOW); // Changed by Copybara. -} - -} // namespace - -struct MjLib::Impl { - const LibMujocoHandle libmujoco_handle; - Impl(const std::string& path, int dlopen_flags) - : libmujoco_handle(DlOpen(path, dlopen_flags)) {} -}; - -// We terminate the program if any of the symbol handles are null. -#define INIT_WITH_DLSYM(name) \ - name(decltype(name)( \ - ABSL_DIE_IF_NULL(dlsym(pimpl_->libmujoco_handle.get(), #name)))) - -#define INIT_WITH_DLSYM_NULLABLE(name) \ - name(decltype(name)(dlsym(pimpl_->libmujoco_handle.get(), #name))) -#define INIT_CALLBACK_WITH_DLSYM(name) \ - name(*(decltype(&name))( \ - ABSL_DIE_IF_NULL(dlsym(pimpl_->libmujoco_handle.get(), #name)))) +#define MJLIB_INIT(name) name(::name) MjLib::MjLib(const std::string& libmujoco_path, int dlopen_flags) - : pimpl_(absl::make_unique(libmujoco_path, dlopen_flags)), - INIT_WITH_DLSYM(mj_defaultVFS), - INIT_WITH_DLSYM(mj_addFileVFS), - INIT_WITH_DLSYM(mj_makeEmptyFileVFS), - INIT_WITH_DLSYM(mj_findFileVFS), - INIT_WITH_DLSYM(mj_deleteFileVFS), - INIT_WITH_DLSYM(mj_deleteVFS), - INIT_WITH_DLSYM(mj_saveLastXML), - INIT_WITH_DLSYM(mj_freeLastXML), - INIT_WITH_DLSYM(mj_printSchema), - INIT_WITH_DLSYM(mj_step), - INIT_WITH_DLSYM(mj_step1), - INIT_WITH_DLSYM(mj_step2), - INIT_WITH_DLSYM(mj_forward), - INIT_WITH_DLSYM(mj_inverse), - INIT_WITH_DLSYM(mj_forwardSkip), - INIT_WITH_DLSYM(mj_inverseSkip), - INIT_WITH_DLSYM(mj_defaultLROpt), - INIT_WITH_DLSYM(mj_defaultSolRefImp), - INIT_WITH_DLSYM(mj_defaultOption), - INIT_WITH_DLSYM(mj_defaultVisual), - INIT_WITH_DLSYM(mj_copyModel), - INIT_WITH_DLSYM(mj_saveModel), - INIT_WITH_DLSYM(mj_loadModel), - INIT_WITH_DLSYM(mj_deleteModel), - INIT_WITH_DLSYM(mj_sizeModel), - INIT_WITH_DLSYM(mj_makeData), - INIT_WITH_DLSYM(mj_copyData), - INIT_WITH_DLSYM(mj_resetData), - INIT_WITH_DLSYM(mj_resetDataDebug), - INIT_WITH_DLSYM(mj_resetDataKeyframe), - INIT_WITH_DLSYM(mj_deleteData), - INIT_WITH_DLSYM(mj_resetCallbacks), - INIT_WITH_DLSYM(mj_setConst), - INIT_WITH_DLSYM(mj_setLengthRange), - INIT_WITH_DLSYM(mj_printModel), - INIT_WITH_DLSYM(mj_printData), - INIT_WITH_DLSYM(mju_printMat), - INIT_WITH_DLSYM(mju_printMatSparse), - INIT_WITH_DLSYM(mj_fwdPosition), - INIT_WITH_DLSYM(mj_fwdVelocity), - INIT_WITH_DLSYM(mj_fwdActuation), - INIT_WITH_DLSYM(mj_fwdAcceleration), - INIT_WITH_DLSYM(mj_fwdConstraint), - INIT_WITH_DLSYM(mj_Euler), - INIT_WITH_DLSYM(mj_RungeKutta), - INIT_WITH_DLSYM(mj_invPosition), - INIT_WITH_DLSYM(mj_invVelocity), - INIT_WITH_DLSYM(mj_invConstraint), - INIT_WITH_DLSYM(mj_compareFwdInv), - INIT_WITH_DLSYM(mj_sensorPos), - INIT_WITH_DLSYM(mj_sensorVel), - INIT_WITH_DLSYM(mj_sensorAcc), - INIT_WITH_DLSYM(mj_energyPos), - INIT_WITH_DLSYM(mj_energyVel), - INIT_WITH_DLSYM(mj_checkPos), - INIT_WITH_DLSYM(mj_checkVel), - INIT_WITH_DLSYM(mj_checkAcc), - INIT_WITH_DLSYM(mj_kinematics), - INIT_WITH_DLSYM(mj_comPos), - INIT_WITH_DLSYM(mj_camlight), - INIT_WITH_DLSYM(mj_tendon), - INIT_WITH_DLSYM(mj_transmission), - INIT_WITH_DLSYM(mj_crb), - INIT_WITH_DLSYM(mj_factorM), - INIT_WITH_DLSYM(mj_solveM), - INIT_WITH_DLSYM(mj_solveM2), - INIT_WITH_DLSYM(mj_comVel), - INIT_WITH_DLSYM(mj_passive), - INIT_WITH_DLSYM(mj_subtreeVel), - INIT_WITH_DLSYM(mj_rne), - INIT_WITH_DLSYM(mj_rnePostConstraint), - INIT_WITH_DLSYM(mj_collision), - INIT_WITH_DLSYM(mj_makeConstraint), - INIT_WITH_DLSYM(mj_projectConstraint), - INIT_WITH_DLSYM(mj_referenceConstraint), - INIT_WITH_DLSYM(mj_constraintUpdate), - INIT_WITH_DLSYM(mj_addContact), - INIT_WITH_DLSYM(mj_isPyramidal), - INIT_WITH_DLSYM(mj_isSparse), - INIT_WITH_DLSYM(mj_isDual), - INIT_WITH_DLSYM(mj_mulJacVec), - INIT_WITH_DLSYM(mj_mulJacTVec), - INIT_WITH_DLSYM(mj_jac), - INIT_WITH_DLSYM(mj_jacBody), - INIT_WITH_DLSYM(mj_jacBodyCom), - INIT_WITH_DLSYM(mj_jacGeom), - INIT_WITH_DLSYM(mj_jacSite), - INIT_WITH_DLSYM(mj_jacPointAxis), - INIT_WITH_DLSYM(mj_name2id), - INIT_WITH_DLSYM(mj_id2name), - INIT_WITH_DLSYM(mj_fullM), - INIT_WITH_DLSYM(mj_mulM), - INIT_WITH_DLSYM(mj_mulM2), - INIT_WITH_DLSYM(mj_addM), - INIT_WITH_DLSYM(mj_applyFT), - INIT_WITH_DLSYM(mj_objectVelocity), - INIT_WITH_DLSYM(mj_objectAcceleration), - INIT_WITH_DLSYM(mj_contactForce), - INIT_WITH_DLSYM(mj_differentiatePos), - INIT_WITH_DLSYM(mj_integratePos), - INIT_WITH_DLSYM(mj_normalizeQuat), - INIT_WITH_DLSYM(mj_local2Global), - INIT_WITH_DLSYM(mj_getTotalmass), - INIT_WITH_DLSYM(mj_setTotalmass), - INIT_WITH_DLSYM(mj_version), - INIT_WITH_DLSYM(mj_ray), - INIT_WITH_DLSYM(mj_rayHfield), - INIT_WITH_DLSYM(mj_rayMesh), - INIT_WITH_DLSYM(mju_rayGeom), - INIT_WITH_DLSYM(mju_raySkin), - INIT_WITH_DLSYM(mjv_defaultCamera), - INIT_WITH_DLSYM(mjv_defaultPerturb), - INIT_WITH_DLSYM(mjv_room2model), - INIT_WITH_DLSYM(mjv_model2room), - INIT_WITH_DLSYM(mjv_cameraInModel), - INIT_WITH_DLSYM(mjv_cameraInRoom), - INIT_WITH_DLSYM(mjv_frustumHeight), - INIT_WITH_DLSYM(mjv_alignToCamera), - INIT_WITH_DLSYM(mjv_moveCamera), - INIT_WITH_DLSYM(mjv_movePerturb), - INIT_WITH_DLSYM(mjv_moveModel), - INIT_WITH_DLSYM(mjv_initPerturb), - INIT_WITH_DLSYM(mjv_applyPerturbPose), - INIT_WITH_DLSYM(mjv_applyPerturbForce), - INIT_WITH_DLSYM(mjv_averageCamera), - INIT_WITH_DLSYM(mjv_select), - INIT_WITH_DLSYM(mjv_defaultOption), - INIT_WITH_DLSYM(mjv_defaultFigure), - INIT_WITH_DLSYM(mjv_initGeom), - INIT_WITH_DLSYM(mjv_makeConnector), - INIT_WITH_DLSYM(mjv_defaultScene), - INIT_WITH_DLSYM(mjv_makeScene), - INIT_WITH_DLSYM(mjv_freeScene), - INIT_WITH_DLSYM(mjv_updateScene), - INIT_WITH_DLSYM(mjv_addGeoms), - INIT_WITH_DLSYM(mjv_makeLights), - INIT_WITH_DLSYM(mjv_updateCamera), - INIT_WITH_DLSYM(mjv_updateSkin), - // Rendering and UI-related symbols may be null if we use the no_gl DSO. - INIT_WITH_DLSYM_NULLABLE(mjr_defaultContext), - INIT_WITH_DLSYM_NULLABLE(mjr_makeContext), - INIT_WITH_DLSYM_NULLABLE(mjr_changeFont), - INIT_WITH_DLSYM_NULLABLE(mjr_addAux), - INIT_WITH_DLSYM_NULLABLE(mjr_freeContext), - INIT_WITH_DLSYM_NULLABLE(mjr_uploadTexture), - INIT_WITH_DLSYM_NULLABLE(mjr_uploadMesh), - INIT_WITH_DLSYM_NULLABLE(mjr_uploadHField), - INIT_WITH_DLSYM_NULLABLE(mjr_restoreBuffer), - INIT_WITH_DLSYM_NULLABLE(mjr_setBuffer), - INIT_WITH_DLSYM_NULLABLE(mjr_readPixels), - INIT_WITH_DLSYM_NULLABLE(mjr_drawPixels), - INIT_WITH_DLSYM_NULLABLE(mjr_blitBuffer), - INIT_WITH_DLSYM_NULLABLE(mjr_setAux), - INIT_WITH_DLSYM_NULLABLE(mjr_blitAux), - INIT_WITH_DLSYM_NULLABLE(mjr_text), - INIT_WITH_DLSYM_NULLABLE(mjr_overlay), - INIT_WITH_DLSYM_NULLABLE(mjr_maxViewport), - INIT_WITH_DLSYM_NULLABLE(mjr_rectangle), - INIT_WITH_DLSYM_NULLABLE(mjr_figure), - INIT_WITH_DLSYM_NULLABLE(mjr_render), - INIT_WITH_DLSYM_NULLABLE(mjr_finish), - INIT_WITH_DLSYM_NULLABLE(mjr_getError), - INIT_WITH_DLSYM_NULLABLE(mjr_findRect), - INIT_WITH_DLSYM_NULLABLE(mjui_themeSpacing), - INIT_WITH_DLSYM_NULLABLE(mjui_themeColor), - INIT_WITH_DLSYM_NULLABLE(mjui_add), - INIT_WITH_DLSYM_NULLABLE(mjui_resize), - INIT_WITH_DLSYM_NULLABLE(mjui_update), - INIT_WITH_DLSYM_NULLABLE(mjui_event), - INIT_WITH_DLSYM_NULLABLE(mjui_render), - INIT_WITH_DLSYM(mju_error), - INIT_WITH_DLSYM(mju_error_i), - INIT_WITH_DLSYM(mju_error_s), - INIT_WITH_DLSYM(mju_warning), - INIT_WITH_DLSYM(mju_warning_i), - INIT_WITH_DLSYM(mju_warning_s), - INIT_WITH_DLSYM(mju_clearHandlers), - INIT_WITH_DLSYM(mju_malloc), - INIT_WITH_DLSYM(mju_free), - INIT_WITH_DLSYM(mj_warning), - INIT_WITH_DLSYM(mju_writeLog), - INIT_WITH_DLSYM(mju_zero3), - INIT_WITH_DLSYM(mju_copy3), - INIT_WITH_DLSYM(mju_scl3), - INIT_WITH_DLSYM(mju_add3), - INIT_WITH_DLSYM(mju_sub3), - INIT_WITH_DLSYM(mju_addTo3), - INIT_WITH_DLSYM(mju_subFrom3), - INIT_WITH_DLSYM(mju_addToScl3), - INIT_WITH_DLSYM(mju_addScl3), - INIT_WITH_DLSYM(mju_normalize3), - INIT_WITH_DLSYM(mju_norm3), - INIT_WITH_DLSYM(mju_dot3), - INIT_WITH_DLSYM(mju_dist3), - INIT_WITH_DLSYM(mju_rotVecMat), - INIT_WITH_DLSYM(mju_rotVecMatT), - INIT_WITH_DLSYM(mju_cross), - INIT_WITH_DLSYM(mju_zero4), - INIT_WITH_DLSYM(mju_unit4), - INIT_WITH_DLSYM(mju_copy4), - INIT_WITH_DLSYM(mju_normalize4), - INIT_WITH_DLSYM(mju_zero), - INIT_WITH_DLSYM(mju_copy), - INIT_WITH_DLSYM(mju_sum), - INIT_WITH_DLSYM(mju_L1), - INIT_WITH_DLSYM(mju_scl), - INIT_WITH_DLSYM(mju_add), - INIT_WITH_DLSYM(mju_sub), - INIT_WITH_DLSYM(mju_addTo), - INIT_WITH_DLSYM(mju_subFrom), - INIT_WITH_DLSYM(mju_addToScl), - INIT_WITH_DLSYM(mju_addScl), - INIT_WITH_DLSYM(mju_normalize), - INIT_WITH_DLSYM(mju_norm), - INIT_WITH_DLSYM(mju_dot), - INIT_WITH_DLSYM(mju_mulMatVec), - INIT_WITH_DLSYM(mju_mulMatTVec), - INIT_WITH_DLSYM(mju_transpose), - INIT_WITH_DLSYM(mju_mulMatMat), - INIT_WITH_DLSYM(mju_mulMatMatT), - INIT_WITH_DLSYM(mju_mulMatTMat), - INIT_WITH_DLSYM(mju_sqrMatTD), - INIT_WITH_DLSYM(mju_transformSpatial), - INIT_WITH_DLSYM(mju_rotVecQuat), - INIT_WITH_DLSYM(mju_negQuat), - INIT_WITH_DLSYM(mju_mulQuat), - INIT_WITH_DLSYM(mju_mulQuatAxis), - INIT_WITH_DLSYM(mju_axisAngle2Quat), - INIT_WITH_DLSYM(mju_quat2Vel), - INIT_WITH_DLSYM(mju_subQuat), - INIT_WITH_DLSYM(mju_quat2Mat), - INIT_WITH_DLSYM(mju_mat2Quat), - INIT_WITH_DLSYM(mju_derivQuat), - INIT_WITH_DLSYM(mju_quatIntegrate), - INIT_WITH_DLSYM(mju_quatZ2Vec), - INIT_WITH_DLSYM(mju_mulPose), - INIT_WITH_DLSYM(mju_negPose), - INIT_WITH_DLSYM(mju_trnVecPose), - INIT_WITH_DLSYM(mju_cholFactor), - INIT_WITH_DLSYM(mju_cholSolve), - INIT_WITH_DLSYM(mju_cholUpdate), - INIT_WITH_DLSYM(mju_eig3), - INIT_WITH_DLSYM(mju_muscleGain), - INIT_WITH_DLSYM(mju_muscleBias), - INIT_WITH_DLSYM(mju_muscleDynamics), - INIT_WITH_DLSYM(mju_encodePyramid), - INIT_WITH_DLSYM(mju_decodePyramid), - INIT_WITH_DLSYM(mju_springDamper), - INIT_WITH_DLSYM(mju_min), - INIT_WITH_DLSYM(mju_max), - INIT_WITH_DLSYM(mju_sign), - INIT_WITH_DLSYM(mju_round), - INIT_WITH_DLSYM(mju_type2Str), - INIT_WITH_DLSYM(mju_str2Type), - INIT_WITH_DLSYM(mju_warningText), - INIT_WITH_DLSYM(mju_isBad), - INIT_WITH_DLSYM(mju_isZero), - INIT_WITH_DLSYM(mju_standardNormal), - INIT_WITH_DLSYM(mju_f2n), - INIT_WITH_DLSYM(mju_n2f), - INIT_WITH_DLSYM(mju_d2n), - INIT_WITH_DLSYM(mju_n2d), - INIT_WITH_DLSYM(mju_insertionSort), - INIT_WITH_DLSYM(mju_Halton), - INIT_WITH_DLSYM(mju_strncpy), - INIT_CALLBACK_WITH_DLSYM(mjcb_passive), - INIT_CALLBACK_WITH_DLSYM(mjcb_control), - INIT_CALLBACK_WITH_DLSYM(mjcb_contactfilter), - INIT_CALLBACK_WITH_DLSYM(mjcb_sensor), - INIT_CALLBACK_WITH_DLSYM(mjcb_time), - INIT_CALLBACK_WITH_DLSYM(mjcb_act_dyn), - INIT_CALLBACK_WITH_DLSYM(mjcb_act_gain), - INIT_CALLBACK_WITH_DLSYM(mjcb_act_bias), - INIT_CALLBACK_WITH_DLSYM(mjCOLLISIONFUNC), - INIT_WITH_DLSYM(mj_loadXML) {} + : MJLIB_INIT(mj_defaultVFS), + MJLIB_INIT(mj_addFileVFS), + MJLIB_INIT(mj_makeEmptyFileVFS), + MJLIB_INIT(mj_findFileVFS), + MJLIB_INIT(mj_deleteFileVFS), + MJLIB_INIT(mj_deleteVFS), + MJLIB_INIT(mj_saveLastXML), + MJLIB_INIT(mj_freeLastXML), + MJLIB_INIT(mj_printSchema), + MJLIB_INIT(mj_step), + MJLIB_INIT(mj_step1), + MJLIB_INIT(mj_step2), + MJLIB_INIT(mj_forward), + MJLIB_INIT(mj_inverse), + MJLIB_INIT(mj_forwardSkip), + MJLIB_INIT(mj_inverseSkip), + MJLIB_INIT(mj_defaultLROpt), + MJLIB_INIT(mj_defaultSolRefImp), + MJLIB_INIT(mj_defaultOption), + MJLIB_INIT(mj_defaultVisual), + MJLIB_INIT(mj_copyModel), + MJLIB_INIT(mj_saveModel), + MJLIB_INIT(mj_loadModel), + MJLIB_INIT(mj_deleteModel), + MJLIB_INIT(mj_sizeModel), + MJLIB_INIT(mj_makeData), + MJLIB_INIT(mj_copyData), + MJLIB_INIT(mj_resetData), + MJLIB_INIT(mj_resetDataDebug), + MJLIB_INIT(mj_resetDataKeyframe), + MJLIB_INIT(mj_deleteData), + MJLIB_INIT(mj_resetCallbacks), + MJLIB_INIT(mj_setConst), + MJLIB_INIT(mj_setLengthRange), + MJLIB_INIT(mj_printModel), + MJLIB_INIT(mj_printData), + MJLIB_INIT(mju_printMat), + MJLIB_INIT(mju_printMatSparse), + MJLIB_INIT(mj_fwdPosition), + MJLIB_INIT(mj_fwdVelocity), + MJLIB_INIT(mj_fwdActuation), + MJLIB_INIT(mj_fwdAcceleration), + MJLIB_INIT(mj_fwdConstraint), + MJLIB_INIT(mj_Euler), + MJLIB_INIT(mj_RungeKutta), + MJLIB_INIT(mj_invPosition), + MJLIB_INIT(mj_invVelocity), + MJLIB_INIT(mj_invConstraint), + MJLIB_INIT(mj_compareFwdInv), + MJLIB_INIT(mj_sensorPos), + MJLIB_INIT(mj_sensorVel), + MJLIB_INIT(mj_sensorAcc), + MJLIB_INIT(mj_energyPos), + MJLIB_INIT(mj_energyVel), + MJLIB_INIT(mj_checkPos), + MJLIB_INIT(mj_checkVel), + MJLIB_INIT(mj_checkAcc), + MJLIB_INIT(mj_kinematics), + MJLIB_INIT(mj_comPos), + MJLIB_INIT(mj_camlight), + MJLIB_INIT(mj_tendon), + MJLIB_INIT(mj_transmission), + MJLIB_INIT(mj_crb), + MJLIB_INIT(mj_factorM), + MJLIB_INIT(mj_solveM), + MJLIB_INIT(mj_solveM2), + MJLIB_INIT(mj_comVel), + MJLIB_INIT(mj_passive), + MJLIB_INIT(mj_subtreeVel), + MJLIB_INIT(mj_rne), + MJLIB_INIT(mj_rnePostConstraint), + MJLIB_INIT(mj_collision), + MJLIB_INIT(mj_makeConstraint), + MJLIB_INIT(mj_projectConstraint), + MJLIB_INIT(mj_referenceConstraint), + MJLIB_INIT(mj_constraintUpdate), + MJLIB_INIT(mj_addContact), + MJLIB_INIT(mj_isPyramidal), + MJLIB_INIT(mj_isSparse), + MJLIB_INIT(mj_isDual), + MJLIB_INIT(mj_mulJacVec), + MJLIB_INIT(mj_mulJacTVec), + MJLIB_INIT(mj_jac), + MJLIB_INIT(mj_jacBody), + MJLIB_INIT(mj_jacBodyCom), + MJLIB_INIT(mj_jacGeom), + MJLIB_INIT(mj_jacSite), + MJLIB_INIT(mj_jacPointAxis), + MJLIB_INIT(mj_name2id), + MJLIB_INIT(mj_id2name), + MJLIB_INIT(mj_fullM), + MJLIB_INIT(mj_mulM), + MJLIB_INIT(mj_mulM2), + MJLIB_INIT(mj_addM), + MJLIB_INIT(mj_applyFT), + MJLIB_INIT(mj_objectVelocity), + MJLIB_INIT(mj_objectAcceleration), + MJLIB_INIT(mj_contactForce), + MJLIB_INIT(mj_differentiatePos), + MJLIB_INIT(mj_integratePos), + MJLIB_INIT(mj_normalizeQuat), + MJLIB_INIT(mj_local2Global), + MJLIB_INIT(mj_getTotalmass), + MJLIB_INIT(mj_setTotalmass), + MJLIB_INIT(mj_version), + MJLIB_INIT(mj_ray), + MJLIB_INIT(mj_rayHfield), + MJLIB_INIT(mj_rayMesh), + MJLIB_INIT(mju_rayGeom), + MJLIB_INIT(mju_raySkin), + MJLIB_INIT(mjv_defaultCamera), + MJLIB_INIT(mjv_defaultPerturb), + MJLIB_INIT(mjv_room2model), + MJLIB_INIT(mjv_model2room), + MJLIB_INIT(mjv_cameraInModel), + MJLIB_INIT(mjv_cameraInRoom), + MJLIB_INIT(mjv_frustumHeight), + MJLIB_INIT(mjv_alignToCamera), + MJLIB_INIT(mjv_moveCamera), + MJLIB_INIT(mjv_movePerturb), + MJLIB_INIT(mjv_moveModel), + MJLIB_INIT(mjv_initPerturb), + MJLIB_INIT(mjv_applyPerturbPose), + MJLIB_INIT(mjv_applyPerturbForce), + MJLIB_INIT(mjv_averageCamera), + MJLIB_INIT(mjv_select), + MJLIB_INIT(mjv_defaultOption), + MJLIB_INIT(mjv_defaultFigure), + MJLIB_INIT(mjv_initGeom), + MJLIB_INIT(mjv_makeConnector), + MJLIB_INIT(mjv_defaultScene), + MJLIB_INIT(mjv_makeScene), + MJLIB_INIT(mjv_freeScene), + MJLIB_INIT(mjv_updateScene), + MJLIB_INIT(mjv_addGeoms), + MJLIB_INIT(mjv_makeLights), + MJLIB_INIT(mjv_updateCamera), + MJLIB_INIT(mjv_updateSkin), + MJLIB_INIT(mjr_defaultContext), + MJLIB_INIT(mjr_makeContext), + MJLIB_INIT(mjr_changeFont), + MJLIB_INIT(mjr_addAux), + MJLIB_INIT(mjr_freeContext), + MJLIB_INIT(mjr_uploadTexture), + MJLIB_INIT(mjr_uploadMesh), + MJLIB_INIT(mjr_uploadHField), + MJLIB_INIT(mjr_restoreBuffer), + MJLIB_INIT(mjr_setBuffer), + MJLIB_INIT(mjr_readPixels), + MJLIB_INIT(mjr_drawPixels), + MJLIB_INIT(mjr_blitBuffer), + MJLIB_INIT(mjr_setAux), + MJLIB_INIT(mjr_blitAux), + MJLIB_INIT(mjr_text), + MJLIB_INIT(mjr_overlay), + MJLIB_INIT(mjr_maxViewport), + MJLIB_INIT(mjr_rectangle), + MJLIB_INIT(mjr_figure), + MJLIB_INIT(mjr_render), + MJLIB_INIT(mjr_finish), + MJLIB_INIT(mjr_getError), + MJLIB_INIT(mjr_findRect), + MJLIB_INIT(mjui_themeSpacing), + MJLIB_INIT(mjui_themeColor), + MJLIB_INIT(mjui_add), + MJLIB_INIT(mjui_resize), + MJLIB_INIT(mjui_update), + MJLIB_INIT(mjui_event), + MJLIB_INIT(mjui_render), + MJLIB_INIT(mju_error), + MJLIB_INIT(mju_error_i), + MJLIB_INIT(mju_error_s), + MJLIB_INIT(mju_warning), + MJLIB_INIT(mju_warning_i), + MJLIB_INIT(mju_warning_s), + MJLIB_INIT(mju_clearHandlers), + MJLIB_INIT(mju_malloc), + MJLIB_INIT(mju_free), + MJLIB_INIT(mj_warning), + MJLIB_INIT(mju_writeLog), + MJLIB_INIT(mju_zero3), + MJLIB_INIT(mju_copy3), + MJLIB_INIT(mju_scl3), + MJLIB_INIT(mju_add3), + MJLIB_INIT(mju_sub3), + MJLIB_INIT(mju_addTo3), + MJLIB_INIT(mju_subFrom3), + MJLIB_INIT(mju_addToScl3), + MJLIB_INIT(mju_addScl3), + MJLIB_INIT(mju_normalize3), + MJLIB_INIT(mju_norm3), + MJLIB_INIT(mju_dot3), + MJLIB_INIT(mju_dist3), + MJLIB_INIT(mju_rotVecMat), + MJLIB_INIT(mju_rotVecMatT), + MJLIB_INIT(mju_cross), + MJLIB_INIT(mju_zero4), + MJLIB_INIT(mju_unit4), + MJLIB_INIT(mju_copy4), + MJLIB_INIT(mju_normalize4), + MJLIB_INIT(mju_zero), + MJLIB_INIT(mju_copy), + MJLIB_INIT(mju_sum), + MJLIB_INIT(mju_L1), + MJLIB_INIT(mju_scl), + MJLIB_INIT(mju_add), + MJLIB_INIT(mju_sub), + MJLIB_INIT(mju_addTo), + MJLIB_INIT(mju_subFrom), + MJLIB_INIT(mju_addToScl), + MJLIB_INIT(mju_addScl), + MJLIB_INIT(mju_normalize), + MJLIB_INIT(mju_norm), + MJLIB_INIT(mju_dot), + MJLIB_INIT(mju_mulMatVec), + MJLIB_INIT(mju_mulMatTVec), + MJLIB_INIT(mju_transpose), + MJLIB_INIT(mju_mulMatMat), + MJLIB_INIT(mju_mulMatMatT), + MJLIB_INIT(mju_mulMatTMat), + MJLIB_INIT(mju_sqrMatTD), + MJLIB_INIT(mju_transformSpatial), + MJLIB_INIT(mju_rotVecQuat), + MJLIB_INIT(mju_negQuat), + MJLIB_INIT(mju_mulQuat), + MJLIB_INIT(mju_mulQuatAxis), + MJLIB_INIT(mju_axisAngle2Quat), + MJLIB_INIT(mju_quat2Vel), + MJLIB_INIT(mju_subQuat), + MJLIB_INIT(mju_quat2Mat), + MJLIB_INIT(mju_mat2Quat), + MJLIB_INIT(mju_derivQuat), + MJLIB_INIT(mju_quatIntegrate), + MJLIB_INIT(mju_quatZ2Vec), + MJLIB_INIT(mju_mulPose), + MJLIB_INIT(mju_negPose), + MJLIB_INIT(mju_trnVecPose), + MJLIB_INIT(mju_cholFactor), + MJLIB_INIT(mju_cholSolve), + MJLIB_INIT(mju_cholUpdate), + MJLIB_INIT(mju_eig3), + MJLIB_INIT(mju_muscleGain), + MJLIB_INIT(mju_muscleBias), + MJLIB_INIT(mju_muscleDynamics), + MJLIB_INIT(mju_encodePyramid), + MJLIB_INIT(mju_decodePyramid), + MJLIB_INIT(mju_springDamper), + MJLIB_INIT(mju_min), + MJLIB_INIT(mju_max), + MJLIB_INIT(mju_sign), + MJLIB_INIT(mju_round), + MJLIB_INIT(mju_type2Str), + MJLIB_INIT(mju_str2Type), + MJLIB_INIT(mju_warningText), + MJLIB_INIT(mju_isBad), + MJLIB_INIT(mju_isZero), + MJLIB_INIT(mju_standardNormal), + MJLIB_INIT(mju_f2n), + MJLIB_INIT(mju_n2f), + MJLIB_INIT(mju_d2n), + MJLIB_INIT(mju_n2d), + MJLIB_INIT(mju_insertionSort), + MJLIB_INIT(mju_Halton), + MJLIB_INIT(mju_strncpy), + MJLIB_INIT(mjcb_passive), + MJLIB_INIT(mjcb_control), + MJLIB_INIT(mjcb_contactfilter), + MJLIB_INIT(mjcb_sensor), + MJLIB_INIT(mjcb_time), + MJLIB_INIT(mjcb_act_dyn), + MJLIB_INIT(mjcb_act_gain), + MJLIB_INIT(mjcb_act_bias), + MJLIB_INIT(mjCOLLISIONFUNC), + MJLIB_INIT(mj_loadXML) {} MjLib::~MjLib() = default; -#undef INIT_CALLBACK_WITH_DLSYM -#undef INIT_WITH_DLSYM_NULLABLE -#undef INIT_WITH_DLSYM +#undef MJLIB_INIT } // namespace dm_robotics diff --git a/cpp/mujoco/src/test_with_mjlib.cc b/cpp/mujoco/src/test_with_mjlib.cc index e843c89..ad84625 100644 --- a/cpp/mujoco/src/test_with_mjlib.cc +++ b/cpp/mujoco/src/test_with_mjlib.cc @@ -18,7 +18,6 @@ #include -// Internal file library include #include "dm_robotics/support/logging.h" #include "dm_robotics/support/status-matchers.h" #include "gmock/gmock.h" @@ -31,14 +30,8 @@ namespace dm_robotics::testing { MjLib* TestWithMjLib::mjlib_ = nullptr; -void TestWithMjLib::SetUpTestSuite() { - mjlib_ = new MjLib( - file::JoinPath(absl::GetFlag(FLAGS_test_srcdir), kMujocoLibNoGlPath), - RTLD_NOW); -} +void TestWithMjLib::SetUpTestSuite() { mjlib_ = new MjLib("", RTLD_NOW); } -void TestWithMjLib::TearDownTestSuite() { - delete mjlib_; -} +void TestWithMjLib::TearDownTestSuite() { delete mjlib_; } } // namespace dm_robotics::testing diff --git a/cpp/mujoco/tests/mjlib_test.cc b/cpp/mujoco/tests/mjlib_test.cc index 05e55d8..fe09edc 100644 --- a/cpp/mujoco/tests/mjlib_test.cc +++ b/cpp/mujoco/tests/mjlib_test.cc @@ -25,7 +25,7 @@ namespace dm_robotics { namespace { TEST(MjlibTest, CanLoadMjLib) { - MjLib mjlib(kMujocoLibNoGlPath, RTLD_NOW); // Load library. + MjLib mjlib("", RTLD_NOW); // Load library. } } // namespace diff --git a/cpp/requirements_external.txt b/cpp/requirements_external.txt index ef78d46..d28abfa 100644 --- a/cpp/requirements_external.txt +++ b/cpp/requirements_external.txt @@ -2,5 +2,5 @@ numpy >= 1.16.0 setuptools >= 38.6.0 pkginfo >= 1.4.2 wheel >= 0.31.0 -dm_control == 1.0.9 -mujoco == 2.3.1.post1 +dm_control == 1.0.15 +mujoco == 3.0.0 diff --git a/cpp/setup.py b/cpp/setup.py index fbb1b9a..7a8f145 100644 --- a/cpp/setup.py +++ b/cpp/setup.py @@ -23,10 +23,12 @@ from setuptools.command.build_ext import build_ext +PRE_DOWNLOADED_MUJOCO_TAR = "/deps/mujoco-3.0.0-linux-x86_64.tar.gz" + PRE_DOWNLOADED_SOURCE_DIRS = { - "abseil-cpp": "/deps/abseil-cpp_215105818dfde3174fe799600bb0f3cae233d0bf", - "osqp-cpp": "/deps/osqp-cpp_8cd904e2b49c24dd41d11f8c6e0adb113dd5e26c", - "osqp": "/deps/osqp_f9fc23d3436e4b17dd2cb95f70cfa1f37d122c24", + "abseil-cpp": "/deps/abseil-cpp_c2435f8342c2d0ed8101cb43adfd605fdc52dca2", + "osqp-cpp": "/deps/osqp-cpp_43433736334d6b515ea4b0247156fea9e56c0d3f", + "osqp": "/deps/osqp_0baddd36bd57ec1cace0a52c6dd9663e8f16df0a", "pybind11": "/deps/pybind11_914c06fb252b6cc3727d0eedab6736e88a3fcb01", "googletest": "/deps/googletest_e2239ee6043f73722e7aa812a459f54a28552929" } @@ -61,11 +63,13 @@ def build_extension(self, ext): cmake_args = [ "-DCMAKE_LIBRARY_OUTPUT_DIRECTORY={}".format(output_directory), "-DPYTHON_EXECUTABLE={}".format(sys.executable), - "-DDMR_PYTHON_VERSION={}.{}".format(sys.version_info.major, - sys.version_info.minor), + "-DDMR_PYTHON_VERSION={}.{}".format( + sys.version_info.major, sys.version_info.minor + ), "-DCMAKE_BUILD_TYPE={}".format(build_type), "-DDM_ROBOTICS_BUILD_TESTS=OFF", "-DDM_ROBOTICS_BUILD_WHEEL=True", + "-DDM_ROBOTICS_MUJOCO_TAR={}".format(PRE_DOWNLOADED_MUJOCO_TAR), "--log-level=VERBOSE", ] diff --git a/py/agentflow/requirements_external.txt b/py/agentflow/requirements_external.txt index 13f295b..a50f9f3 100644 --- a/py/agentflow/requirements_external.txt +++ b/py/agentflow/requirements_external.txt @@ -1,6 +1,6 @@ numpy >= 1.16.0 -dm_control == 1.0.9 -mujoco == 2.3.1.post1 +dm_control == 1.0.15 +mujoco == 3.0.0 opencv-python >= 3.4.0, <= 4.6.0.66 attrs >= 20.3.0 pydot >= 1.2.4 diff --git a/py/geometry/requirements_external.txt b/py/geometry/requirements_external.txt index cc711cb..1c10ba5 100644 --- a/py/geometry/requirements_external.txt +++ b/py/geometry/requirements_external.txt @@ -1,4 +1,4 @@ numpy >= 1.16.0 -dm_control == 1.0.9 -mujoco == 2.3.1.post1 +dm_control == 1.0.15 +mujoco == 3.0.0 six >= 1.16.0 diff --git a/py/manipulation/requirements_external.txt b/py/manipulation/requirements_external.txt index efc3b76..119430d 100644 --- a/py/manipulation/requirements_external.txt +++ b/py/manipulation/requirements_external.txt @@ -1,5 +1,5 @@ absl-py >= 0.9.0 numpy >= 1.16.0 typing-extensions >= 3.7.4 -dm_control == 1.0.9 -mujoco == 2.3.1.post1 +dm_control == 1.0.15 +mujoco == 3.0.0 diff --git a/py/moma/requirements_external.txt b/py/moma/requirements_external.txt index 80623d4..4e17f2a 100644 --- a/py/moma/requirements_external.txt +++ b/py/moma/requirements_external.txt @@ -1,6 +1,6 @@ numpy >= 1.16.0 -dm_control == 1.0.9 -mujoco == 2.3.1.post1 +dm_control == 1.0.15 +mujoco == 3.0.0 opencv-python >= 3.4.0, <= 4.6.0.66 attrs >= 20.3.0 pydot >= 1.2.4