Skip to content

Commit e83b7d3

Browse files
authored
Merge deepmind branch into main
Deepmind merge
2 parents 48b8b5f + dfbf002 commit e83b7d3

File tree

30 files changed

+120
-480
lines changed

30 files changed

+120
-480
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-
893c4042302e5a5738dbc462466e746f2bbc1ea5
59+
3.1.1
6060
CACHE STRING "Git revision for MuJoCo."
6161
)
6262

6363
set(MUJOCO_MPC_MENAGERIE_GIT_TAG
64-
94ea114fa8c60a0fd542c8e1ffeb997204acbea2
64+
8ef01e87fffaa8ec634a4826c5b2092733b2f3c8
6565
CACHE STRING "Git revision for MuJoCo Menagerie."
6666
)
6767

mjpc/CMakeLists.txt

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -44,12 +44,8 @@ add_library(
4444
tasks/bimanual/bimanual.h
4545
tasks/cartpole/cartpole.cc
4646
tasks/cartpole/cartpole.h
47-
tasks/cube/solve.cc
48-
tasks/cube/solve.h
4947
tasks/fingers/fingers.cc
5048
tasks/fingers/fingers.h
51-
tasks/hand/hand.cc
52-
tasks/hand/hand.h
5349
tasks/humanoid/stand/stand.cc
5450
tasks/humanoid/stand/stand.h
5551
tasks/humanoid/tracking/tracking.cc
@@ -66,6 +62,10 @@ add_library(
6662
tasks/panda/panda.h
6763
tasks/particle/particle.cc
6864
tasks/particle/particle.h
65+
tasks/rubik/solve.cc
66+
tasks/rubik/solve.h
67+
tasks/shadow_reorient/hand.cc
68+
tasks/shadow_reorient/hand.h
6969
tasks/quadrotor/quadrotor.cc
7070
tasks/quadrotor/quadrotor.h
7171
tasks/quadruped/quadruped.cc

mjpc/app.cc

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,8 @@
4040
#include "mjpc/threadpool.h"
4141
#include "mjpc/utilities.h"
4242

43-
ABSL_FLAG(std::string, task, "", "Which model to load on startup.");
43+
ABSL_FLAG(std::string, task, "Quadruped Flat",
44+
"Which model to load on startup.");
4445
ABSL_FLAG(bool, planner_enabled, false,
4546
"If true, the planner will run on startup");
4647
ABSL_FLAG(float, sim_percent_realtime, 100,
@@ -392,7 +393,7 @@ void PhysicsLoop(mj::Simulate& sim) {
392393

393394
namespace mjpc {
394395

395-
MjpcApp::MjpcApp(std::vector<std::shared_ptr<mjpc::Task>> tasks, int task_id) {
396+
MjpcApp::MjpcApp(std::vector<std::shared_ptr<mjpc::Task>> tasks) {
396397
// MJPC
397398
printf("MuJoCo MPC (MJPC)\n");
398399

@@ -415,8 +416,8 @@ MjpcApp::MjpcApp(std::vector<std::shared_ptr<mjpc::Task>> tasks, int task_id) {
415416

416417
sim->agent->SetTaskList(std::move(tasks));
417418
std::string task_name = absl::GetFlag(FLAGS_task);
418-
if (task_name.empty()) {
419-
sim->agent->gui_task_id = task_id;
419+
if (task_name.empty()) { // shouldn't happen, flag has a default value
420+
sim->agent->gui_task_id = 0;
420421
} else {
421422
sim->agent->gui_task_id = sim->agent->GetTaskIdByName(task_name);
422423
if (sim->agent->gui_task_id == -1) {
@@ -519,8 +520,8 @@ mj::Simulate* MjpcApp::Sim() {
519520
return sim.get();
520521
}
521522

522-
void StartApp(std::vector<std::shared_ptr<mjpc::Task>> tasks, int task_id) {
523-
MjpcApp app(std::move(tasks), task_id);
523+
void StartApp(std::vector<std::shared_ptr<mjpc::Task>> tasks) {
524+
MjpcApp app(std::move(tasks));
524525
app.Start();
525526
}
526527

mjpc/app.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
namespace mjpc {
2525
class MjpcApp {
2626
public:
27-
MjpcApp(std::vector<std::shared_ptr<mjpc::Task>> tasks, int task_id = 0);
27+
explicit MjpcApp(std::vector<std::shared_ptr<mjpc::Task>> tasks);
2828
MjpcApp(const MjpcApp&) = delete;
2929
MjpcApp& operator=(const MjpcApp&) = delete;
3030
~MjpcApp();
@@ -34,7 +34,7 @@ class MjpcApp {
3434
::mujoco::Simulate* Sim();
3535
};
3636

37-
void StartApp(std::vector<std::shared_ptr<mjpc::Task>> tasks, int task_id = 0);
37+
void StartApp(std::vector<std::shared_ptr<mjpc::Task>> tasks);
3838

3939
} // namespace mjpc
4040

mjpc/main.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,6 @@ int main(int argc, char** argv) {
4747
#endif
4848
absl::ParseCommandLine(argc, argv);
4949

50-
mjpc::StartApp(mjpc::GetTasks(), 11); // start with quadruped flat
50+
mjpc::StartApp(mjpc::GetTasks());
5151
return 0;
5252
}

mjpc/planners/cross_entropy/planner.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -322,7 +322,7 @@ void CrossEntropyPlanner::ResamplePolicy(int horizon) {
322322

323323
LinearRange(resampled_policy.times.data(), time_shift,
324324
resampled_policy.times[0], num_spline_points);
325-
325+
326326
resampled_policy.representation = policy.representation;
327327
}
328328

mjpc/planners/sampling/planner.cc

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -267,8 +267,13 @@ void SamplingPlanner::AddNoiseToPolicy(int i) {
267267
int shift = i * (model->nu * kMaxTrajectoryHorizon);
268268

269269
// sample noise
270-
for (int k = 0; k < num_parameters; k++) {
271-
noise[k + shift] = absl::Gaussian<double>(gen_, 0.0, noise_exploration);
270+
for (int t = 0; t < num_spline_points; t++) {
271+
for (int k = 0; k < model->nu; k++) {
272+
double scale = 0.5 * (model->actuator_ctrlrange[2 * k + 1] -
273+
model->actuator_ctrlrange[2 * k]);
274+
noise[shift + t * model->nu + k] =
275+
absl::Gaussian<double>(gen_, 0.0, scale * noise_exploration);
276+
}
272277
}
273278

274279
// add noise

mjpc/simulate.cc

Lines changed: 3 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -1163,10 +1163,7 @@ void UiEvent(mjuiState* state) {
11631163
sim->screenshotrequest.store(true);
11641164
break;
11651165
}
1166-
}
1167-
1168-
// option section
1169-
else if (it && it->sectionid==SECT_OPTION) {
1166+
} else if (it && it->sectionid == SECT_OPTION) {
11701167
if (it->pdata == &sim->spacing) {
11711168
sim->ui0.spacing = mjui_themeSpacing(sim->spacing);
11721169
sim->ui1.spacing = mjui_themeSpacing(sim->spacing);
@@ -1184,37 +1181,16 @@ void UiEvent(mjuiState* state) {
11841181
// modify UI
11851182
UiModify(&sim->ui0, state, &sim->platform_ui->mjr_context());
11861183
UiModify(&sim->ui1, state, &sim->platform_ui->mjr_context());
1187-
}
11881184

1189-
// simulation section
1190-
else if (it && it->sectionid==SECT_SIMULATION) {
1185+
} else if (it && it->sectionid == SECT_SIMULATION) {
11911186
switch (it->itemid) {
11921187
case 1: // Reset
11931188
if (m) {
1194-
mj_resetData(m, d);
1189+
mj_resetDataKeyframe(m, d, mj_name2id(m, mjOBJ_KEY, "home"));
11951190
mj_forward(m, d);
11961191
UpdateProfiler(sim);
11971192
UpdateSensor(sim);
11981193
UpdateSettings(sim);
1199-
// set initial qpos via keyframe
1200-
double* key_qpos = mjpc::KeyQPosByName(sim->mnew, sim->dnew,
1201-
"home");
1202-
if (key_qpos) {
1203-
mju_copy(sim->dnew->qpos, key_qpos, sim->mnew->nq);
1204-
}
1205-
// set initial qvel via keyframe
1206-
double* key_qvel = mjpc::KeyQVelByName(sim->mnew, sim->dnew,
1207-
"home");
1208-
if (key_qvel) {
1209-
mju_copy(sim->dnew->qvel, key_qvel, sim->mnew->nv);
1210-
}
1211-
// set initial act via keyframe
1212-
double* act = mjpc::KeyActByName(sim->mnew, sim->dnew,
1213-
"home");
1214-
if (act) {
1215-
mju_copy(sim->dnew->act, act, sim->mnew->na);
1216-
}
1217-
12181194
sim->agent->PlotReset();
12191195
}
12201196
break;

mjpc/tasks/CMakeLists.txt

Lines changed: 20 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -64,19 +64,21 @@ add_custom_target(
6464
## Menagerie models
6565
COMMAND ${CMAKE_COMMAND} -E copy
6666
${menagerie_SOURCE_DIR}/shadow_hand/right_hand.xml
67-
${CMAKE_CURRENT_BINARY_DIR}/hand/right_hand.xml
67+
${CMAKE_CURRENT_BINARY_DIR}/shadow_reorient/right_hand.xml
6868
COMMAND ${CMAKE_COMMAND} -E copy
6969
${menagerie_SOURCE_DIR}/wonik_allegro/right_hand.xml
7070
${CMAKE_CURRENT_BINARY_DIR}/allegro/right_hand.xml
71+
COMMAND ${CMAKE_COMMAND} -E copy_directory
72+
${menagerie_SOURCE_DIR}/shadow_hand/assets
73+
${CMAKE_CURRENT_BINARY_DIR}/shadow_reorient/assets
74+
7175
COMMAND ${CMAKE_COMMAND} -E copy_directory
7276
${menagerie_SOURCE_DIR}/wonik_allegro/assets
7377
${CMAKE_CURRENT_BINARY_DIR}/allegro/assets
7478
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/allegro/right_hand_modified.xml
7579
${CMAKE_CURRENT_BINARY_DIR}/allegro/right_hand.xml
7680
<${CMAKE_CURRENT_SOURCE_DIR}/allegro/right_hand.xml.patch
77-
COMMAND ${CMAKE_COMMAND} -E copy_directory
78-
${menagerie_SOURCE_DIR}/shadow_hand/assets
79-
${CMAKE_CURRENT_BINARY_DIR}/hand/assets
81+
8082
COMMAND ${CMAKE_COMMAND} -E copy
8183
${menagerie_SOURCE_DIR}/franka_emika_panda/panda.xml
8284
${CMAKE_CURRENT_BINARY_DIR}/panda/panda.xml
@@ -86,6 +88,7 @@ add_custom_target(
8688
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/panda/panda_modified.xml
8789
${CMAKE_CURRENT_BINARY_DIR}/panda/panda.xml
8890
<${CMAKE_CURRENT_SOURCE_DIR}/panda/panda.xml.patch
91+
8992
COMMAND ${CMAKE_COMMAND} -E copy
9093
${menagerie_SOURCE_DIR}/unitree_a1/a1.xml
9194
${CMAKE_CURRENT_BINARY_DIR}/quadruped/a1.xml
@@ -95,12 +98,14 @@ add_custom_target(
9598
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/quadruped/a1_modified.xml
9699
${CMAKE_CURRENT_BINARY_DIR}/quadruped/a1.xml
97100
<${CMAKE_CURRENT_SOURCE_DIR}/quadruped/a1.xml.patch
101+
98102
COMMAND ${CMAKE_COMMAND} -E copy_directory
99103
${menagerie_SOURCE_DIR}/franka_emika_panda
100104
${CMAKE_CURRENT_BINARY_DIR}/manipulation
101105
COMMAND ${CMAKE_COMMAND} -E copy_directory
102106
${menagerie_SOURCE_DIR}/robotiq_2f85
103107
${CMAKE_CURRENT_BINARY_DIR}/manipulation
108+
104109
COMMAND ${CMAKE_COMMAND} -E copy
105110
${menagerie_SOURCE_DIR}/skydio_x2/x2.xml
106111
${CMAKE_CURRENT_BINARY_DIR}/quadrotor/quadrotor.xml
@@ -110,31 +115,32 @@ add_custom_target(
110115
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/quadrotor/quadrotor_modified.xml
111116
${CMAKE_CURRENT_BINARY_DIR}/quadrotor/quadrotor.xml
112117
<${CMAKE_CURRENT_SOURCE_DIR}/quadrotor/quadrotor.xml.patch
118+
113119
## Cube solve task
114120
# copy cube model from MuJoCo
115121
COMMAND ${CMAKE_COMMAND} -E copy
116122
${mujoco_SOURCE_DIR}/model/cube/cube_3x3x3.xml
117-
${CMAKE_CURRENT_BINARY_DIR}/cube/cube_3x3x3.xml
123+
${CMAKE_CURRENT_BINARY_DIR}/rubik/cube_3x3x3.xml
118124
# copy cube assets from MuJoCo
119125
COMMAND ${CMAKE_COMMAND} -E copy_directory
120126
${mujoco_SOURCE_DIR}/model/cube/assets
121-
${CMAKE_CURRENT_BINARY_DIR}/cube/assets
127+
${CMAKE_CURRENT_BINARY_DIR}/rubik/assets
122128
# modified cube model for task
123-
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/cube/cube_3x3x3_modified.xml
124-
${CMAKE_CURRENT_BINARY_DIR}/cube/cube_3x3x3.xml
125-
<${CMAKE_CURRENT_SOURCE_DIR}/cube/cube_3x3x3.xml.patch
129+
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/rubik/cube_3x3x3_modified.xml
130+
${CMAKE_CURRENT_BINARY_DIR}/rubik/cube_3x3x3.xml
131+
<${CMAKE_CURRENT_SOURCE_DIR}/rubik/cube_3x3x3.xml.patch
126132
# modified cube model to transition model for scramble mode
127-
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/cube/transition_model.xml
128-
${CMAKE_CURRENT_BINARY_DIR}/cube/cube_3x3x3.xml
129-
<${CMAKE_CURRENT_SOURCE_DIR}/cube/transition_model.xml.patch
133+
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/rubik/transition_model.xml
134+
${CMAKE_CURRENT_BINARY_DIR}/rubik/cube_3x3x3.xml
135+
<${CMAKE_CURRENT_SOURCE_DIR}/rubik/transition_model.xml.patch
130136
# copy hand model from Menagerie
131137
COMMAND ${CMAKE_COMMAND} -E copy
132138
${menagerie_SOURCE_DIR}/shadow_hand/right_hand.xml
133-
${CMAKE_CURRENT_BINARY_DIR}/cube/right_hand.xml
139+
${CMAKE_CURRENT_BINARY_DIR}/rubik/right_hand.xml
134140
# copy hand assets from Menagerie
135141
COMMAND ${CMAKE_COMMAND} -E copy_directory
136142
${menagerie_SOURCE_DIR}/shadow_hand/assets
137-
${CMAKE_CURRENT_BINARY_DIR}/cube/assets
143+
${CMAKE_CURRENT_BINARY_DIR}/rubik/assets
138144

139145
# ALOHA
140146
COMMAND ${CMAKE_COMMAND} -E copy_directory

mjpc/tasks/allegro/task.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,7 @@
5858
<!-- Measurements we want to use -->
5959
<framepos name="cube_goal_position" objtype="site" objname="grasp_site"/>
6060
<framequat name="cube_goal_orientation" objtype="body" objname="goal"/>
61+
<framepos name="trace0" objtype="body" objname="cube"/>
6162
</sensor>
6263

6364
<include file="../common_assets/reorientation_cube.xml"/>

0 commit comments

Comments
 (0)