Skip to content

Commit

Permalink
Merge of 1f78168
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 690624747
Change-Id: Ibd4199b2b861e6a52acaa6aad861af72337745c4
  • Loading branch information
copybara-github committed Oct 28, 2024
2 parents a16d1db + 1f78168 commit abb3a11
Show file tree
Hide file tree
Showing 17 changed files with 985 additions and 51 deletions.
113 changes: 89 additions & 24 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -72,48 +72,110 @@ Humanoid motion-capture tracking:

[![Tracking](http://img.youtube.com/vi/tEBVK-MO1Sw/hqdefault.jpg)](https://www.youtube.com/watch?v=tEBVK-MO1Sw)


## Graphical User Interface

For a detailed dive of the graphical user interface, see the
[MJPC GUI](docs/GUI.md) documentation.

## Installation
MJPC is tested with [Ubuntu 20.04](https://releases.ubuntu.com/focal/) and [macOS-12](https://www.apple.com/by/macos/monterey/). In principle, other versions and Windows operating system should work with MJPC, but these are not tested.

### Prerequisites
Operating system specific dependencies:

#### macOS
Install [Xcode](https://developer.apple.com/xcode/).

Install `ninja` and `zlib`:
```sh
brew install ninja zlib
```

#### Ubuntu 20.04
```sh
sudo apt-get update && sudo apt-get install cmake libgl1-mesa-dev libxinerama-dev libxcursor-dev libxrandr-dev libxi-dev ninja-build zlib1g-dev clang-12
```

### Clone MuJoCo MPC
```sh
git clone https://github.com/google-deepmind/mujoco_mpc
```

### Build and Run MJPC GUI application
1. Change directory:
```sh
cd mujoco_mpc
```

2. Create and change to build directory:
```sh
mkdir build
cd build
```

3. Configure:

#### macOS-12
```sh
cmake .. -DCMAKE_BUILD_TYPE:STRING=Release -G Ninja -DMJPC_BUILD_GRPC_SERVICE:BOOL=ON
```

#### Ubuntu 20.04
```sh
cmake .. -DCMAKE_BUILD_TYPE:STRING=Release -G Ninja -DCMAKE_C_COMPILER:STRING=clang-12 -DCMAKE_CXX_COMPILER:STRING=clang++-12 -DMJPC_BUILD_GRPC_SERVICE:BOOL=ON
```
**Note: gRPC is a large dependency and can take 10-20 minutes to initially download.**

4. Build
```sh
cmake --build . --config=Release
```

6. Run GUI application
```sh
cd bin
./mjpc
```

You will need [CMake](https://cmake.org/) and a working C++20 compiler to build
MJPC. We recommend using [VSCode](https://code.visualstudio.com/) and 2 of its
### Build and Run MJPC GUI application using VSCode
We recommend using [VSCode](https://code.visualstudio.com/) and 2 of its
extensions ([CMake Tools](https://marketplace.visualstudio.com/items?itemName=ms-vscode.cmake-tools)
and [C/C++](https://marketplace.visualstudio.com/items?itemName=ms-vscode.cpptools))
to simplify the build process.

1. Clone the repository: `git clone https://github.com/google-deepmind/mujoco_mpc.git`
1. Open the cloned directory `mujoco_mpc`.
2. Configure the project with CMake (a pop-up should appear in VSCode)
3. Build and run the `mjpc` target in "release" mode (VSCode defaults to
3. Set compiler to `clang-12`.
4. Build and run the `mjpc` target in "release" mode (VSCode defaults to
"debug"). This will open and run the graphical user interface.

### macOS
Additionally, install [Xcode](https://developer.apple.com/xcode/).

### Ubuntu
Additionally, install:
```shell
sudo apt-get install libgl1-mesa-dev libxinerama-dev libxcursor-dev libxrandr-dev libxi-dev ninja-build
```

### Build Issues
If you encounter build issues, please see the
[Github Actions configuration](https://github.com/google-deepmind/mujoco_mpc/blob/main/.github/workflows/build.yml).
This provides the exact setup we use for building MJPC for testing.

We recommend building with `clang` and not `gcc`.
This provides the exact setup we use for building MJPC for testing with Ubuntu 20.04 and macOS-12.

# Python API
We provide a simple Python API for MJPC. This API is still experimental and expects some more experience from its users. For example, the correct usage requires that the model (defined in Python) and the MJPC task (i.e., the residual and transition functions defined in C++) are compatible with each other. Currently, the Python API does not provide any particular error handling for verifying this compatibility and may be difficult to debug without more in-depth knowledge about MuJoCo and MJPC.

We provide a simple Python API for MJPC. This API is still experimental and expects some more experience from its users. For example, the correct usage requires that the model (defined in Python) and the MJPC task (i.e., the residual and transition functions defined in C++) are compatible with each other. Currently, the Python API does not provide any particular error handling for verifying this compatibility and may be difficult to debug without more in-depth knowledge about mujoco and MJPC.
## Installation

### Prerequisites
1. Build MJPC (see instructions above).

2. Python 3.10

## Installing via Pip
First, build MJPC (see above).
3. (Optionally) Create a conda environment with **Python 3.10**:
```sh
conda create -n mjpc python=3.10
conda activate mjpc
```

4. Install MuJoCo
```sh
pip install mujoco
```

### Install API
Next, change to the python directory:
```sh
cd python
Expand All @@ -129,11 +191,14 @@ Test that installation was successful:
python "mujoco_mpc/agent_test.py"
```

Additionally, the [Python version of MuJoCo](https://pypi.org/project/mujoco/#history) should match the MJPC version (this information can be found in the terminal while the application is running).

Example scripts are found in `python/mujoco_mpc/demos`. For example from `python/`:
```sh
python mujoco_mpc/demos/agent/cartpole_gui.py
```
will run the MJPC GUI application using MuJoCo's passive viewer via Python.

## Example Usage
See [cartpole.py](python/mujoco_mpc/demos/agent/cartpole.py) for example usage for planning.
### Python API Installation Issues
If your installation fails or is terminated prematurely, we recommend deleting the MJPC build directory and starting from scratch as the build will likely be corrupted. Additionally, delete the files generated during the installation process from the `python/` directory.

## Predictive Control

Expand Down
4 changes: 4 additions & 0 deletions mjpc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,10 @@ add_library(
tasks/cartpole/cartpole.h
tasks/fingers/fingers.cc
tasks/fingers/fingers.h
tasks/humanoid/interact/interact.cc
tasks/humanoid/interact/interact.h
tasks/humanoid/interact/contact_keyframe.cc
tasks/humanoid/interact/contact_keyframe.h
tasks/humanoid/stand/stand.cc
tasks/humanoid/stand/stand.h
tasks/humanoid/tracking/tracking.cc
Expand Down
39 changes: 22 additions & 17 deletions mjpc/grpc/agent_service.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,12 @@ using ::agent::GetAllModesRequest;
using ::agent::GetAllModesResponse;
using ::agent::GetBestTrajectoryRequest;
using ::agent::GetBestTrajectoryResponse;
using ::agent::GetResidualsRequest;
using ::agent::GetResidualsResponse;
using ::agent::GetCostValuesAndWeightsRequest;
using ::agent::GetCostValuesAndWeightsResponse;
using ::agent::GetModeRequest;
using ::agent::GetModeResponse;
using ::agent::GetResidualsRequest;
using ::agent::GetResidualsResponse;
using ::agent::GetStateRequest;
using ::agent::GetStateResponse;
using ::agent::GetTaskParametersRequest;
Expand Down Expand Up @@ -115,8 +115,7 @@ grpc::Status AgentService::Init(grpc::ServerContext* context,
<< "Multiple instances of AgentService detected.";
agent_model = agent_.GetModel();
// copy the model before agent model's timestep and integrator are updated
CHECK_EQ(model, nullptr)
<< "Multiple instances of AgentService detected.";
CHECK_EQ(model, nullptr) << "Multiple instances of AgentService detected.";
model = mj_copyModel(nullptr, agent_model);
data_ = mj_makeData(model);
rollout_data_.reset(mj_makeData(model));
Expand Down Expand Up @@ -179,18 +178,25 @@ grpc::Status AgentService::GetAction(grpc::ServerContext* context,
if (!Initialized()) {
return {grpc::StatusCode::FAILED_PRECONDITION, "Init not called."};
}
return grpc_agent_util::GetAction(
// get action
auto out = grpc_agent_util::GetAction(
request, &agent_, model, rollout_data_.get(), &rollout_state_, response);
// set data
auto action = response->action().data();
for (int i = 0; i < model->nu; i++) {
data_->ctrl[i] = action[i];
}
return out;
}

grpc::Status AgentService::GetResiduals(
grpc::ServerContext* context, const GetResidualsRequest* request,
GetResidualsResponse* response) {
grpc::Status AgentService::GetResiduals(grpc::ServerContext* context,
const GetResidualsRequest* request,
GetResidualsResponse* response) {
if (!Initialized()) {
return {grpc::StatusCode::FAILED_PRECONDITION, "Init not called."};
}
return grpc_agent_util::GetResiduals(request, &agent_, model,
data_, response);
return grpc_agent_util::GetResiduals(request, &agent_, model, data_,
response);
}

grpc::Status AgentService::GetCostValuesAndWeights(
Expand Down Expand Up @@ -268,9 +274,9 @@ grpc::Status AgentService::GetTaskParameters(
return grpc_agent_util::GetTaskParameters(request, &agent_, response);
}

grpc::Status AgentService::SetCostWeights(
grpc::ServerContext* context, const SetCostWeightsRequest* request,
SetCostWeightsResponse* response) {
grpc::Status AgentService::SetCostWeights(grpc::ServerContext* context,
const SetCostWeightsRequest* request,
SetCostWeightsResponse* response) {
if (!Initialized()) {
return {grpc::StatusCode::FAILED_PRECONDITION, "Init not called."};
}
Expand Down Expand Up @@ -343,10 +349,9 @@ grpc::Status AgentService::GetBestTrajectory(
return grpc::Status::OK;
}


grpc::Status AgentService::SetAnything(
grpc::ServerContext* context, const SetAnythingRequest* request,
SetAnythingResponse* response) {
grpc::Status AgentService::SetAnything(grpc::ServerContext* context,
const SetAnythingRequest* request,
SetAnythingResponse* response) {
if (!Initialized()) {
return {grpc::StatusCode::FAILED_PRECONDITION, "Init not called."};
}
Expand Down
37 changes: 37 additions & 0 deletions mjpc/tasks/humanoid/interact/contact_keyframe.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
// Copyright 2022 DeepMind Technologies Limited
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "mjpc/tasks/humanoid/interact/contact_keyframe.h"

namespace mjpc::humanoid {

void ContactPair::Reset() {
body1 = kNotSelectedInteract;
body2 = kNotSelectedInteract;
geom1 = kNotSelectedInteract;
geom2 = kNotSelectedInteract;
for (int i = 0; i < 3; i++) {
local_pos1[i] = 0.;
local_pos2[i] = 0.;
}
}

void ContactKeyframe::Reset() {
name.clear();
for (auto& contact_pair : contact_pairs) contact_pair.Reset();

facing_target.clear();
weight.clear();
}
} // namespace mjpc::humanoid
64 changes: 64 additions & 0 deletions mjpc/tasks/humanoid/interact/contact_keyframe.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
// Copyright 2022 DeepMind Technologies Limited
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MJPC_TASKS_HUMANOID_INTERACT_CONTACT_KEYFRAME_H_
#define MJPC_TASKS_HUMANOID_INTERACT_CONTACT_KEYFRAME_H_

#include <map>
#include <string>
#include <vector>

#include <mujoco/mujoco.h>

namespace mjpc::humanoid {

// ---------- Constants ----------------- //
constexpr int kNotSelectedInteract = -1;
constexpr int kNumberOfContactPairsInteract = 5;

class ContactPair {
public:
int body1, body2, geom1, geom2;
mjtNum local_pos1[3], local_pos2[3];

ContactPair()
: body1(kNotSelectedInteract),
body2(kNotSelectedInteract),
geom1(kNotSelectedInteract),
geom2(kNotSelectedInteract),
local_pos1{0.},
local_pos2{0.} {}

void Reset();
};

class ContactKeyframe {
public:
std::string name;
ContactPair contact_pairs[kNumberOfContactPairsInteract];

// the direction on the xy-plane for the torso to point towards
std::vector<mjtNum> facing_target;

// weight of all residual terms (name -> value map)
std::map<std::string, mjtNum> weight;

ContactKeyframe() : name(""), contact_pairs{}, facing_target(), weight() {}

void Reset();
};

} // namespace mjpc::humanoid

#endif // MJPC_TASKS_HUMANOID_INTERACT_CONTACT_KEYFRAME_H_
Loading

0 comments on commit abb3a11

Please sign in to comment.