Skip to content

Commit

Permalink
Update MuJoCo dep to v3.0.0 and remove MjLib from the public paramete…
Browse files Browse the repository at this point in the history
…rs API in the Cartesian 6d Mapper.

PiperOrigin-RevId: 576104568
Change-Id: I7a42ba2f95f7608d0eec8b8822ad51c3c1e157c9
  • Loading branch information
josechenf authored and copybara-github committed Oct 24, 2023
1 parent dc8e438 commit 4725cc1
Show file tree
Hide file tree
Showing 21 changed files with 625 additions and 797 deletions.
5 changes: 2 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand All @@ -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.

Expand Down
28 changes: 25 additions & 3 deletions cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -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.
Expand All @@ -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
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
36 changes: 19 additions & 17 deletions cpp/controllers/lsqp/src/cartesian_6d_to_joint_velocity_mapper.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down Expand Up @@ -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;
Expand All @@ -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;
Expand All @@ -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;
Expand All @@ -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;
Expand Down Expand Up @@ -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;
}

Expand Down Expand Up @@ -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.");
Expand Down Expand Up @@ -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(
Expand Down Expand Up @@ -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) {
Expand Down Expand Up @@ -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)),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
11 changes: 1 addition & 10 deletions cpp/controllers_py/cartesian_6d_to_joint_velocity_mapper.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -271,13 +272,6 @@ enabled. This overload should only be used if nullspace control is not enabled.
using PybindGeomGroup = std::vector<std::string>;
using PybindCollisionPair = std::pair<PybindGeomGroup, PybindGeomGroup>;

// 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.
Expand All @@ -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;
}

Expand Down
38 changes: 0 additions & 38 deletions cpp/controllers_py/pybind_utils.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@

#include "pybind_utils.h" // controller

#include <dlfcn.h>
#include <errno.h>
#include <string.h>
#include <sys/stat.h>
Expand Down Expand Up @@ -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<std::string>();
// Not all MuJoCo releases have __version__, they do have mj_versionString.
const auto version = mujoco.attr("mj_versionString")().cast<std::string>();
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 =
Expand Down
12 changes: 0 additions & 12 deletions cpp/controllers_py/pybind_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
1 change: 1 addition & 0 deletions cpp/least_squares_qp/testing/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Loading

0 comments on commit 4725cc1

Please sign in to comment.