Skip to content

Commit b844928

Browse files
authored
Merge pull request #349 from google-deepmind/deepmind
2 parents 1f78168 + abb3a11 commit b844928

File tree

32 files changed

+206
-179
lines changed

32 files changed

+206
-179
lines changed

CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -56,12 +56,12 @@ set(MUJOCO_BUILD_TESTS OFF)
5656
set(MUJOCO_TEST_PYTHON_UTIL OFF)
5757

5858
set(MUJOCO_MPC_MUJOCO_GIT_TAG
59-
3.1.4
59+
088079eff0450e32b98ee743141780ed68307506
6060
CACHE STRING "Git revision for MuJoCo."
6161
)
6262

6363
set(MUJOCO_MPC_MENAGERIE_GIT_TAG
64-
aff360ad958cb0e45d8f740816b1aacad84e9282
64+
d82891f8b6c576f9f6a9df308f3a1155ebedbc40
6565
CACHE STRING "Git revision for MuJoCo Menagerie."
6666
)
6767

README.md

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,12 @@ Quadruped task:
5858

5959
[![Quadruped](http://img.youtube.com/vi/esLuwaWz4oE/hqdefault.jpg)](https://www.youtube.com/watch?v=esLuwaWz4oE)
6060

61+
62+
Bimanual manipulation:
63+
64+
[![Bimanual](http://img.youtube.com/vi/aCNCKVThKIE/hqdefault.jpg)](https://www.youtube.com/watch?v=aCNCKVThKIE)
65+
66+
6167
Rubik's cube 10-move unscramble:
6268

6369
[![Unscramble](http://img.youtube.com/vi/ZRRvVWV-Muk/hqdefault.jpg)](https://www.youtube.com/watch?v=ZRRvVWV-Muk)

cmake/MpcOptions.cmake

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -103,6 +103,10 @@ if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU" OR (CMAKE_CXX_COMPILER_ID MATCHES "Clang
103103
endif()
104104
endif()
105105

106+
if(NOT CMAKE_INTERPROCEDURAL_OPTIMIZATION AND (CMAKE_BUILD_TYPE AND NOT CMAKE_BUILD_TYPE STREQUAL "Debug"))
107+
set(CMAKE_INTERPROCEDURAL_OPTIMIZATION ON)
108+
endif()
109+
106110
include(MujocoHarden)
107111
set(EXTRA_COMPILE_OPTIONS ${EXTRA_COMPILE_OPTIONS} ${MUJOCO_HARDEN_COMPILE_OPTIONS})
108112
set(EXTRA_LINK_OPTIONS ${EXTRA_LINK_OPTIONS} ${MUJOCO_HARDEN_LINK_OPTIONS})

mjpc/agent.cc

Lines changed: 7 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -451,8 +451,8 @@ int Agent::SetModeByName(std::string_view name) {
451451
void Agent::ModifyScene(mjvScene* scn) {
452452
// if acting is off make all geom colors grayscale
453453
if (!action_enabled) {
454-
int cube = mj_name2id(model_, mjOBJ_TEXTURE, "cube");
455-
int graycube = mj_name2id(model_, mjOBJ_TEXTURE, "graycube");
454+
int cube = mj_name2id(model_, mjOBJ_MATERIAL, "cube");
455+
int graycube = mj_name2id(model_, mjOBJ_MATERIAL, "graycube");
456456
for (int i = 0; i < scn->ngeom; i++) {
457457
mjvGeom* g = scn->geoms + i;
458458
// skip static and decor geoms
@@ -463,8 +463,8 @@ void Agent::ModifyScene(mjvScene* scn) {
463463
double rgb_average = (g->rgba[0] + g->rgba[1] + g->rgba[2]) / 3;
464464
g->rgba[0] = g->rgba[1] = g->rgba[2] = rgb_average;
465465
// specifically for the hand task, make grayscale cube.
466-
if (cube > -1 && graycube > -1 && g->texid == cube) {
467-
g->texid = graycube;
466+
if (cube > -1 && graycube > -1 && g->matid == cube) {
467+
g->matid = graycube;
468468
}
469469
}
470470
}
@@ -508,14 +508,10 @@ void Agent::ModifyScene(mjvScene* scn) {
508508
color);
509509

510510
// make geometry
511-
mjv_makeConnector(
511+
mjv_connector(
512512
&scn->geoms[scn->ngeom], mjGEOM_CAPSULE, width,
513-
winner->trace[3 * num_trace * i + 3 * j],
514-
winner->trace[3 * num_trace * i + 1 + 3 * j],
515-
winner->trace[3 * num_trace * i + 2 + 3 * j],
516-
winner->trace[3 * num_trace * (i + 1) + 3 * j],
517-
winner->trace[3 * num_trace * (i + 1) + 1 + 3 * j],
518-
winner->trace[3 * num_trace * (i + 1) + 2 + 3 * j]);
513+
winner->trace.data() + 3 * num_trace * i + 3 * j,
514+
winner->trace.data() + 3 * num_trace * (i + 1) + 3 * j);
519515
// increment number of geometries
520516
scn->ngeom += 1;
521517
}

mjpc/grpc/agent_service.cc

Lines changed: 14 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -35,12 +35,12 @@ using ::agent::GetAllModesRequest;
3535
using ::agent::GetAllModesResponse;
3636
using ::agent::GetBestTrajectoryRequest;
3737
using ::agent::GetBestTrajectoryResponse;
38-
using ::agent::GetResidualsRequest;
39-
using ::agent::GetResidualsResponse;
4038
using ::agent::GetCostValuesAndWeightsRequest;
4139
using ::agent::GetCostValuesAndWeightsResponse;
4240
using ::agent::GetModeRequest;
4341
using ::agent::GetModeResponse;
42+
using ::agent::GetResidualsRequest;
43+
using ::agent::GetResidualsResponse;
4444
using ::agent::GetStateRequest;
4545
using ::agent::GetStateResponse;
4646
using ::agent::GetTaskParametersRequest;
@@ -115,8 +115,7 @@ grpc::Status AgentService::Init(grpc::ServerContext* context,
115115
<< "Multiple instances of AgentService detected.";
116116
agent_model = agent_.GetModel();
117117
// copy the model before agent model's timestep and integrator are updated
118-
CHECK_EQ(model, nullptr)
119-
<< "Multiple instances of AgentService detected.";
118+
CHECK_EQ(model, nullptr) << "Multiple instances of AgentService detected.";
120119
model = mj_copyModel(nullptr, agent_model);
121120
data_ = mj_makeData(model);
122121
rollout_data_.reset(mj_makeData(model));
@@ -190,14 +189,14 @@ grpc::Status AgentService::GetAction(grpc::ServerContext* context,
190189
return out;
191190
}
192191

193-
grpc::Status AgentService::GetResiduals(
194-
grpc::ServerContext* context, const GetResidualsRequest* request,
195-
GetResidualsResponse* response) {
192+
grpc::Status AgentService::GetResiduals(grpc::ServerContext* context,
193+
const GetResidualsRequest* request,
194+
GetResidualsResponse* response) {
196195
if (!Initialized()) {
197196
return {grpc::StatusCode::FAILED_PRECONDITION, "Init not called."};
198197
}
199-
return grpc_agent_util::GetResiduals(request, &agent_, model,
200-
data_, response);
198+
return grpc_agent_util::GetResiduals(request, &agent_, model, data_,
199+
response);
201200
}
202201

203202
grpc::Status AgentService::GetCostValuesAndWeights(
@@ -275,9 +274,9 @@ grpc::Status AgentService::GetTaskParameters(
275274
return grpc_agent_util::GetTaskParameters(request, &agent_, response);
276275
}
277276

278-
grpc::Status AgentService::SetCostWeights(
279-
grpc::ServerContext* context, const SetCostWeightsRequest* request,
280-
SetCostWeightsResponse* response) {
277+
grpc::Status AgentService::SetCostWeights(grpc::ServerContext* context,
278+
const SetCostWeightsRequest* request,
279+
SetCostWeightsResponse* response) {
281280
if (!Initialized()) {
282281
return {grpc::StatusCode::FAILED_PRECONDITION, "Init not called."};
283282
}
@@ -350,10 +349,9 @@ grpc::Status AgentService::GetBestTrajectory(
350349
return grpc::Status::OK;
351350
}
352351

353-
354-
grpc::Status AgentService::SetAnything(
355-
grpc::ServerContext* context, const SetAnythingRequest* request,
356-
SetAnythingResponse* response) {
352+
grpc::Status AgentService::SetAnything(grpc::ServerContext* context,
353+
const SetAnythingRequest* request,
354+
SetAnythingResponse* response) {
357355
if (!Initialized()) {
358356
return {grpc::StatusCode::FAILED_PRECONDITION, "Init not called."};
359357
}

mjpc/grpc/direct_service.cc

Lines changed: 2 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -74,9 +74,7 @@ grpc::Status DirectService::Init(grpc::ServerContext* context,
7474
// mjVFS structs need to be allocated on the heap, because it's ~2MB
7575
auto vfs = std::make_unique<mjVFS>();
7676
mj_defaultVFS(vfs.get());
77-
mj_makeEmptyFileVFS(vfs.get(), file, mjb.size());
78-
int file_idx = mj_findFileVFS(vfs.get(), file);
79-
memcpy(vfs->filedata[file_idx], mjb.data(), mjb.size());
77+
mj_addBufferVFS(vfs.get(), file, mjb.data(), mjb.size());
8078
tmp_model = {mj_loadModel(file, vfs.get()), mj_deleteModel};
8179
mj_deleteFileVFS(vfs.get(), file);
8280
} else if (request->has_model() && request->model().has_xml()) {
@@ -88,9 +86,7 @@ grpc::Status DirectService::Init(grpc::ServerContext* context,
8886
// mjVFS structs need to be allocated on the heap, because it's ~2MB
8987
auto vfs = std::make_unique<mjVFS>();
9088
mj_defaultVFS(vfs.get());
91-
mj_makeEmptyFileVFS(vfs.get(), file, model_xml.size());
92-
int file_idx = mj_findFileVFS(vfs.get(), file);
93-
memcpy(vfs->filedata[file_idx], model_xml.data(), model_xml.size());
89+
mj_addBufferVFS(vfs.get(), file, model_xml.data(), model_xml.size());
9490
tmp_model = {mj_loadXML(file, vfs.get(), load_error, sizeof(load_error)),
9591
mj_deleteModel};
9692
mj_deleteFileVFS(vfs.get(), file);

mjpc/grpc/filter_service.cc

Lines changed: 2 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,6 @@
1414

1515
#include "mjpc/grpc/filter_service.h"
1616

17-
#include <cstring>
1817
#include <memory>
1918
#include <sstream>
2019
#include <string_view>
@@ -70,9 +69,7 @@ grpc::Status FilterService::Init(grpc::ServerContext* context,
7069
// mjVFS structs need to be allocated on the heap, because it's ~2MB
7170
auto vfs = std::make_unique<mjVFS>();
7271
mj_defaultVFS(vfs.get());
73-
mj_makeEmptyFileVFS(vfs.get(), file, mjb.size());
74-
int file_idx = mj_findFileVFS(vfs.get(), file);
75-
memcpy(vfs->filedata[file_idx], mjb.data(), mjb.size());
72+
mj_addBufferVFS(vfs.get(), file, mjb.data(), mjb.size());
7673
tmp_model = {mj_loadModel(file, vfs.get()), mj_deleteModel};
7774
mj_deleteFileVFS(vfs.get(), file);
7875
} else if (request->has_model() && request->model().has_xml()) {
@@ -84,9 +81,7 @@ grpc::Status FilterService::Init(grpc::ServerContext* context,
8481
// mjVFS structs need to be allocated on the heap, because it's ~2MB
8582
auto vfs = std::make_unique<mjVFS>();
8683
mj_defaultVFS(vfs.get());
87-
mj_makeEmptyFileVFS(vfs.get(), file, model_xml.size());
88-
int file_idx = mj_findFileVFS(vfs.get(), file);
89-
memcpy(vfs->filedata[file_idx], model_xml.data(), model_xml.size());
84+
mj_addBufferVFS(vfs.get(), file, model_xml.data(), model_xml.size());
9085
tmp_model = {mj_loadXML(file, vfs.get(), load_error, sizeof(load_error)),
9186
mj_deleteModel};
9287
mj_deleteFileVFS(vfs.get(), file);

mjpc/grpc/grpc_agent_util.cc

Lines changed: 2 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,6 @@
1414

1515
#include "mjpc/grpc/grpc_agent_util.h"
1616

17-
#include <cstring>
1817
#include <memory>
1918
#include <sstream>
2019
#include <string>
@@ -521,9 +520,7 @@ mjpc::UniqueMjModel LoadModelFromString(std::string_view xml, char* error,
521520
// mjVFS structs need to be allocated on the heap, because it's ~2MB
522521
auto vfs = std::make_unique<mjVFS>();
523522
mj_defaultVFS(vfs.get());
524-
mj_makeEmptyFileVFS(vfs.get(), file, xml.size());
525-
int file_idx = mj_findFileVFS(vfs.get(), file);
526-
std::memcpy(vfs->filedata[file_idx], xml.data(), xml.size());
523+
mj_addBufferVFS(vfs.get(), file, xml.data(), xml.size());
527524
mjpc::UniqueMjModel m = {mj_loadXML(file, vfs.get(), error, error_size),
528525
mj_deleteModel};
529526
mj_deleteFileVFS(vfs.get(), file);
@@ -535,9 +532,7 @@ mjpc::UniqueMjModel LoadModelFromBytes(std::string_view mjb) {
535532
// mjVFS structs need to be allocated on the heap, because it's ~2MB
536533
auto vfs = std::make_unique<mjVFS>();
537534
mj_defaultVFS(vfs.get());
538-
mj_makeEmptyFileVFS(vfs.get(), file, mjb.size());
539-
int file_idx = mj_findFileVFS(vfs.get(), file);
540-
memcpy(vfs->filedata[file_idx], mjb.data(), mjb.size());
535+
mj_addBufferVFS(vfs.get(), file, mjb.data(), mjb.size());
541536
mjpc::UniqueMjModel m = {mj_loadModel(file, vfs.get()), mj_deleteModel};
542537
mj_deleteFileVFS(vfs.get(), file);
543538
return m;

mjpc/planners/cross_entropy/planner.cc

Lines changed: 3 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -465,14 +465,10 @@ void CrossEntropyPlanner::Traces(mjvScene* scn) {
465465
// elite index
466466
int idx = trajectory_order[k];
467467
// make geometry
468-
mjv_makeConnector(
468+
mjv_connector(
469469
&scn->geoms[scn->ngeom], mjGEOM_LINE, width,
470-
trajectory[idx].trace[3 * task->num_trace * i + 3 * j],
471-
trajectory[idx].trace[3 * task->num_trace * i + 1 + 3 * j],
472-
trajectory[idx].trace[3 * task->num_trace * i + 2 + 3 * j],
473-
trajectory[idx].trace[3 * task->num_trace * (i + 1) + 3 * j],
474-
trajectory[idx].trace[3 * task->num_trace * (i + 1) + 1 + 3 * j],
475-
trajectory[idx].trace[3 * task->num_trace * (i + 1) + 2 + 3 * j]);
470+
trajectory[idx].trace.data() + 3*task->num_trace * i + 3 * j,
471+
trajectory[idx].trace.data() + 3*task->num_trace * (i + 1) + 3 * j);
476472

477473
// increment number of geometries
478474
scn->ngeom += 1;

mjpc/planners/gradient/planner.cc

Lines changed: 3 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -448,14 +448,10 @@ void GradientPlanner::Traces(mjvScene* scn) {
448448
color);
449449

450450
// make geometry
451-
mjv_makeConnector(
451+
mjv_connector(
452452
&scn->geoms[scn->ngeom], mjGEOM_LINE, width,
453-
trajectory[k].trace[3 * task->num_trace * i + 3 * j],
454-
trajectory[k].trace[3 * task->num_trace * i + 1 + 3 * j],
455-
trajectory[k].trace[3 * task->num_trace * i + 2 + 3 * j],
456-
trajectory[k].trace[3 * task->num_trace * (i + 1) + 3 * j],
457-
trajectory[k].trace[3 * task->num_trace * (i + 1) + 1 + 3 * j],
458-
trajectory[k].trace[3 * task->num_trace * (i + 1) + 2 + 3 * j]);
453+
trajectory[k].trace.data() + 3 * task->num_trace * i + 3 * j,
454+
trajectory[k].trace.data() + 3 * task->num_trace * (i + 1) + 3 * j);
459455

460456
// increment number of geometries
461457
scn->ngeom += 1;

0 commit comments

Comments
 (0)