Skip to content

Commit 50a0159

Browse files
authored
Merge deepmind branch into main
Merge deepmind branch into main
2 parents 42eef44 + 063ff93 commit 50a0159

File tree

12 files changed

+259
-27
lines changed

12 files changed

+259
-27
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ set(MUJOCO_BUILD_TESTS OFF)
5656
set(MUJOCO_TEST_PYTHON_UTIL OFF)
5757

5858
set(MUJOCO_MPC_MUJOCO_GIT_TAG
59-
3.1.1
59+
24eb4c9f092da7dd245a116841a5325a0fb359b9
6060
CACHE STRING "Git revision for MuJoCo."
6161
)
6262

mjpc/CMakeLists.txt

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -40,8 +40,10 @@ add_library(
4040
tasks/acrobot/acrobot.h
4141
tasks/allegro/allegro.cc
4242
tasks/allegro/allegro.h
43-
tasks/bimanual/bimanual.cc
44-
tasks/bimanual/bimanual.h
43+
tasks/bimanual/handover/handover.cc
44+
tasks/bimanual/handover/handover.h
45+
tasks/bimanual/reorient/reorient.cc
46+
tasks/bimanual/reorient/reorient.h
4547
tasks/cartpole/cartpole.cc
4648
tasks/cartpole/cartpole.h
4749
tasks/fingers/fingers.cc

mjpc/tasks/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -116,11 +116,11 @@ add_custom_target(
116116
${CMAKE_CURRENT_BINARY_DIR}/quadrotor/quadrotor.xml
117117
<${CMAKE_CURRENT_SOURCE_DIR}/quadrotor/quadrotor.xml.patch
118118

119-
## Cube reorientation
119+
## Cube reorientation
120120
# patch cube from common assets
121121
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/common_assets/cube_modified_shadow_reorient.xml
122122
${CMAKE_CURRENT_BINARY_DIR}/common_assets/reorientation_cube.xml
123-
<${CMAKE_CURRENT_SOURCE_DIR}/shadow_reorient/cube.xml.patch
123+
<${CMAKE_CURRENT_SOURCE_DIR}/common_assets/cube.xml.patch
124124

125125
## Cube solve task
126126
# copy cube model from MuJoCo

mjpc/tasks/bimanual/aloha.patch

Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,43 @@
11
diff --git a/aloha.xml b/aloha.xml
22
--- a/aloha.xml
33
+++ b/aloha.xml
4+
@@ -1,23 +1,23 @@
5+
<mujoco model="aloha">
6+
- <compiler angle="radian" meshdir="assets" autolimits="true"/>
7+
+ <compiler angle="radian" autolimits="true"/>
8+
9+
<option cone="elliptic" impratio="10"/>
10+
11+
<asset>
12+
<material name="black" rgba="0.15 0.15 0.15 1"/>
13+
14+
- <mesh file="vx300s_1_base.stl" scale="0.001 0.001 0.001"/>
15+
- <mesh file="vx300s_2_shoulder.stl" scale="0.001 0.001 0.001"/>
16+
- <mesh file="vx300s_3_upper_arm.stl" scale="0.001 0.001 0.001"/>
17+
- <mesh file="vx300s_4_upper_forearm.stl" scale="0.001 0.001 0.001"/>
18+
- <mesh file="vx300s_5_lower_forearm.stl" scale="0.001 0.001 0.001"/>
19+
- <mesh file="vx300s_6_wrist.stl" scale="0.001 0.001 0.001"/>
20+
- <mesh file="vx300s_7_gripper_prop.stl"/>
21+
- <mesh file="vx300s_7_gripper_bar.stl"/>
22+
- <mesh file="vx300s_7_gripper_wrist_mount.stl"/>
23+
- <mesh file="vx300s_8_custom_finger_left.stl"/>
24+
- <mesh file="vx300s_8_custom_finger_right.stl"/>
25+
- <mesh file="d405_solid.stl"/>
26+
+ <mesh file="assets/vx300s_1_base.stl" scale="0.001 0.001 0.001"/>
27+
+ <mesh file="assets/vx300s_2_shoulder.stl" scale="0.001 0.001 0.001"/>
28+
+ <mesh file="assets/vx300s_3_upper_arm.stl" scale="0.001 0.001 0.001"/>
29+
+ <mesh file="assets/vx300s_4_upper_forearm.stl" scale="0.001 0.001 0.001"/>
30+
+ <mesh file="assets/vx300s_5_lower_forearm.stl" scale="0.001 0.001 0.001"/>
31+
+ <mesh file="assets/vx300s_6_wrist.stl" scale="0.001 0.001 0.001"/>
32+
+ <mesh file="assets/vx300s_7_gripper_prop.stl"/>
33+
+ <mesh file="assets/vx300s_7_gripper_bar.stl"/>
34+
+ <mesh file="assets/vx300s_7_gripper_wrist_mount.stl"/>
35+
+ <mesh file="assets/vx300s_8_custom_finger_left.stl"/>
36+
+ <mesh file="assets/vx300s_8_custom_finger_right.stl"/>
37+
+ <mesh file="assets/d405_solid.stl"/>
38+
</asset>
39+
40+
<default>
441
@@ -284,5 +285,5 @@
542
<joint joint1="right/left_finger" joint2="right/right_finger" polycoef="0 1 0 0 0"/>
643
</equality>

mjpc/tasks/bimanual/bimanual.cc renamed to mjpc/tasks/bimanual/handover/handover.cc

Lines changed: 7 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -12,20 +12,20 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "mjpc/tasks/bimanual/bimanual.h"
15+
#include "mjpc/tasks/bimanual/handover/handover.h"
1616

1717
#include <string>
1818

1919
#include <mujoco/mujoco.h>
2020
#include "mjpc/utilities.h"
2121

22-
namespace mjpc {
23-
std::string Bimanual::XmlPath() const {
24-
return GetModelPath("bimanual/task.xml");
22+
namespace mjpc::aloha {
23+
std::string Handover::XmlPath() const {
24+
return GetModelPath("bimanual/handover/task.xml");
2525
}
26-
std::string Bimanual::Name() const { return "Bimanual"; }
26+
std::string Handover::Name() const { return "Bimanual Handover"; }
2727

28-
void Bimanual::ResidualFn::Residual(const mjModel* model, const mjData* data,
28+
void Handover::ResidualFn::Residual(const mjModel* model, const mjData* data,
2929
double* residual) const {
3030
int counter = 0;
3131

@@ -47,7 +47,4 @@ void Bimanual::ResidualFn::Residual(const mjModel* model, const mjData* data,
4747
CheckSensorDim(model, counter);
4848
}
4949

50-
void mjpc::Bimanual::TransitionLocked(mjModel* model, mjData* data) {
51-
}
52-
53-
} // namespace mjpc
50+
} // namespace mjpc::aloha

mjpc/tasks/bimanual/bimanual.h renamed to mjpc/tasks/bimanual/handover/handover.h

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -12,30 +12,29 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef MJPC_MJPC_TASKS_BIMANUAL_BIMANUAL_H_
16-
#define MJPC_MJPC_TASKS_BIMANUAL_BIMANUAL_H_
15+
#ifndef MJPC_MJPC_TASKS_BIMANUAL_HANDOVER_HANDOVER_H_
16+
#define MJPC_MJPC_TASKS_BIMANUAL_HANDOVER_HANDOVER_H_
1717

1818
#include <memory>
1919
#include <string>
2020

2121
#include <mujoco/mujoco.h>
2222
#include "mjpc/task.h"
2323

24-
namespace mjpc {
25-
class Bimanual : public Task {
24+
namespace mjpc::aloha {
25+
class Handover : public Task {
2626
public:
2727
std::string Name() const override;
2828
std::string XmlPath() const override;
2929

3030
class ResidualFn : public BaseResidualFn {
3131
public:
32-
explicit ResidualFn(const Bimanual* task) : BaseResidualFn(task) {}
32+
explicit ResidualFn(const Handover* task) : BaseResidualFn(task) {}
3333
void Residual(const mjModel* model, const mjData* data,
3434
double* residual) const override;
3535
};
3636

37-
Bimanual() : residual_(this) {}
38-
void TransitionLocked(mjModel* model, mjData* data) override;
37+
Handover() : residual_(this) {}
3938

4039
protected:
4140
std::unique_ptr<mjpc::ResidualFn> ResidualLocked() const override {
@@ -49,4 +48,4 @@ class Bimanual : public Task {
4948
} // namespace mjpc
5049

5150

52-
#endif // MJPC_MJPC_TASKS_BIMANUAL_BIMANUAL_H_
51+
#endif // MJPC_MJPC_TASKS_BIMANUAL_HANDOVER_HANDOVER_H_

mjpc/tasks/bimanual/task.xml renamed to mjpc/tasks/bimanual/handover/task.xml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
<mujoco model="aloha">
2-
<include file="../common.xml"/>
2+
<include file="../../common.xml"/>
33

44
<size memory="1M"/>
55

@@ -28,7 +28,7 @@
2828
<scale framelength=".3" framewidth=".03"/>
2929
</visual>
3030

31-
<include file="aloha_cartesian.xml"/>
31+
<include file="../aloha_cartesian.xml"/>
3232

3333
<worldbody>
3434
<light pos="0 -0.1 0.5" dir="0 0.2 -1" diffuse="0.7 0.7 0.7" specular="0.3 0.3 0.3"
Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
1+
// Copyright 2022 DeepMind Technologies Limited
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "mjpc/tasks/bimanual/reorient/reorient.h"
16+
17+
#include <string>
18+
19+
#include <mujoco/mujoco.h>
20+
#include "mjpc/utilities.h"
21+
22+
namespace mjpc::aloha {
23+
std::string Reorient::XmlPath() const {
24+
return GetModelPath("bimanual/reorient/task.xml");
25+
}
26+
std::string Reorient::Name() const { return "Bimanual Reorient"; }
27+
28+
void Reorient::ResidualFn::Residual(const mjModel* model, const mjData* data,
29+
double* residual) const {
30+
int counter = 0;
31+
32+
// reach
33+
double* left_gripper = SensorByName(model, data, "left/gripper");
34+
double* box = SensorByName(model, data, "box");
35+
mju_sub3(residual + counter, left_gripper, box);
36+
counter += 3;
37+
38+
double* right_gripper = SensorByName(model, data, "right/gripper");
39+
mju_sub3(residual + counter, right_gripper, box);
40+
counter += 3;
41+
42+
// bring
43+
double* target = SensorByName(model, data, "target");
44+
mju_sub3(residual + counter, box, target);
45+
counter += 3;
46+
47+
// ---------- Cube orientation ----------
48+
double *cube_orientation = SensorByName(model, data, "cube_orientation");
49+
double *goal_cube_orientation =
50+
SensorByName(model, data, "cube_goal_orientation");
51+
mju_normalize4(goal_cube_orientation);
52+
53+
mju_subQuat(residual + counter, goal_cube_orientation, cube_orientation);
54+
counter += 3;
55+
56+
// ---------- Cube linear velocity ----------
57+
double *cube_linear_velocity =
58+
SensorByName(model, data, "cube_linear_velocity");
59+
60+
mju_copy(residual + counter, cube_linear_velocity, 3);
61+
counter += 3;
62+
63+
CheckSensorDim(model, counter);
64+
}
65+
66+
} // namespace mjpc::aloha
Lines changed: 51 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
// Copyright 2024 DeepMind Technologies Limited
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef MJPC_MJPC_TASKS_BIMANUAL_REORIENT_REORIENT_H_
16+
#define MJPC_MJPC_TASKS_BIMANUAL_REORIENT_REORIENT_H_
17+
18+
#include <memory>
19+
#include <string>
20+
21+
#include <mujoco/mujoco.h>
22+
#include "mjpc/task.h"
23+
24+
namespace mjpc::aloha {
25+
class Reorient : public Task {
26+
public:
27+
std::string Name() const override;
28+
std::string XmlPath() const override;
29+
30+
class ResidualFn : public BaseResidualFn {
31+
public:
32+
explicit ResidualFn(const Reorient* task) : BaseResidualFn(task) {}
33+
void Residual(const mjModel* model, const mjData* data,
34+
double* residual) const override;
35+
};
36+
37+
Reorient() : residual_(this) {}
38+
39+
protected:
40+
std::unique_ptr<mjpc::ResidualFn> ResidualLocked() const override {
41+
return std::make_unique<ResidualFn>(this);
42+
}
43+
ResidualFn* InternalResidual() override { return &residual_; }
44+
45+
private:
46+
ResidualFn residual_;
47+
};
48+
} // namespace mjpc::aloha
49+
50+
51+
#endif // MJPC_MJPC_TASKS_BIMANUAL_REORIENT_REORIENT_H_

mjpc/tasks/bimanual/reorient/task.xml

Lines changed: 78 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,78 @@
1+
<mujoco model="aloha">
2+
<include file="../../common.xml"/>
3+
4+
<size memory="1M"/>
5+
6+
<asset>
7+
<texture name="groundplane" type="2d" builtin="flat" rgb1="0.20000000000000001 0.29999999999999999 0.40000000000000002" rgb2="0.10000000000000001 0.20000000000000001 0.29999999999999999" mark="edge" markrgb="0.50000000000000004 0.50000000000000004 0.50000000000000004" width="200" height="200"/>
8+
<material name="groundplane" texture="groundplane" texrepeat="2 2" texuniform="true" reflectance="0.20000000000000001"/>
9+
</asset>
10+
11+
<custom>
12+
<numeric name="agent_planner" data="0" />
13+
<numeric name="agent_horizon" data="1.0" />
14+
<numeric name="agent_timestep" data="0.01" />
15+
<numeric name="agent_sample_width" data="0.0025" />
16+
<numeric name="agent_policy_width" data="0.0035" />
17+
<numeric name="sampling_exploration" data="0.5" />
18+
<numeric name="sampling_trajectories" data="120"/>
19+
<numeric name="sampling_spline_points" data="4" />
20+
<numeric name="gradient_spline_points" data="6" />
21+
</custom>
22+
23+
<statistic extent="1.5" center="0.0 0.35 0.2"/>
24+
25+
<visual>
26+
<quality shadowsize="8192"/>
27+
<global azimuth="90" elevation="-30"/>
28+
<scale framelength=".3" framewidth=".03"/>
29+
</visual>
30+
31+
<!-- since the included reorientation_cube brings its own sensors, the residuals must be specified first -->
32+
<sensor>
33+
<user name="Reach L" dim="3" user="2 0.1 0 .5 0.005"/>
34+
<user name="Reach R" dim="3" user="2 0.1 0 .5 0.005"/>
35+
<user name="Bring" dim="3" user="2 1 0 1 0.003"/>
36+
<user name="Cube Orientation" dim="3" user="0 0.02 0 .2" />
37+
<user name="Cube Velocity" dim="3" user="0 .01 0 .2" />
38+
<framequat name="cube_goal_orientation" objtype="body" objname="goal"/>
39+
<framepos name="left/gripper" objtype="site" objname="left/gripper"/>
40+
<framepos name="right/gripper" objtype="site" objname="right/gripper"/>
41+
<framepos name="box" objtype="body" objname="cube"/>
42+
<framepos name="target" objtype="body" objname="box_goal_mocap"/>
43+
<framepos name="trace0" objtype="body" objname="cube"/>
44+
<framepos name="trace1" objtype="site" objname="left/gripper"/>
45+
<framepos name="trace2" objtype="site" objname="right/gripper"/>
46+
</sensor>
47+
48+
<include file="../aloha_cartesian.xml"/>
49+
<include file="../../common_assets/reorientation_cube.xml"/>
50+
51+
<worldbody>
52+
<light pos="0 -0.1 0.5" dir="0 0.2 -1" diffuse="0.7 0.7 0.7" specular="0.3 0.3 0.3"
53+
directional="true" castshadow="true"/>
54+
<geom name="floor" pos="0 0 -0.75" size="0 0 0.05" type="plane" material="groundplane"/>
55+
<body name="table" pos="0 0 -0.75">
56+
<geom name="table" pos="0 0 0.6509" size="0.61 0.37 0.1" type="box" class="collision"/>
57+
<geom name="table_visual" pos="0 0 0.6509" size="0.61 0.37 0.1" type="box" rgba="0.4 0.4 0.4 1" conaffinity="0" contype="0"/>
58+
</body>
59+
<body mocap="true" name="box_goal_mocap">
60+
<geom group="2" size="0.02" rgba="1 0.4 0.4 1" conaffinity="0" contype="0"/>
61+
</body>
62+
<body name="goal" pos="0.325 0.17 0.0475">
63+
<joint type="ball" damping="0.001"/>
64+
<geom type="box" size=".03 .03 .03" mass=".124" material="cube" contype="0" conaffinity="0"/>
65+
</body>
66+
</worldbody>
67+
<keyframe>
68+
<key name="home" qpos=
69+
"0 -0.96 1.16 0 -0.3 0 0.002 0.002
70+
0 -0.96 1.16 0 -0.3 0 0.002 0.002
71+
0.02 0.02 0.075 1 0 0 0
72+
1 0 0 0
73+
"
74+
mpos="0 0 0.25"
75+
act= "-0.1 0 0 0 0 0 0.03 0.1 0 0 0 0 0 0.03"
76+
ctrl="-0.1 0 0 0 0 0 0.03 0.1 0 0 0 0 0 0.03"/>
77+
</keyframe>
78+
</mujoco>

mjpc/tasks/tasks.cc

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,8 @@
2020
#include "mjpc/task.h"
2121
#include "mjpc/tasks/acrobot/acrobot.h"
2222
#include "mjpc/tasks/allegro/allegro.h"
23-
#include "mjpc/tasks/bimanual/bimanual.h"
23+
#include "mjpc/tasks/bimanual/handover/handover.h"
24+
#include "mjpc/tasks/bimanual/reorient/reorient.h"
2425
#include "mjpc/tasks/cartpole/cartpole.h"
2526
#include "mjpc/tasks/fingers/fingers.h"
2627
#include "mjpc/tasks/humanoid/stand/stand.h"
@@ -44,7 +45,8 @@ std::vector<std::shared_ptr<Task>> GetTasks() {
4445
return {
4546
std::make_shared<Acrobot>(),
4647
std::make_shared<Allegro>(),
47-
std::make_shared<Bimanual>(),
48+
std::make_shared<aloha::Handover>(),
49+
std::make_shared<aloha::Reorient>(),
4850
std::make_shared<Cartpole>(),
4951
std::make_shared<Fingers>(),
5052
std::make_shared<humanoid::Stand>(),

0 commit comments

Comments
 (0)