Skip to content

Commit 9bdc85e

Browse files
erez-tomcopybara-github
authored andcommitted
Add an ALOHA task to MJPC.
PiperOrigin-RevId: 604575665 Change-Id: I8565db95ee089a7c1a507c545b677452e5d2a00c
1 parent be5e4f6 commit 9bdc85e

File tree

6 files changed

+209
-0
lines changed

6 files changed

+209
-0
lines changed

mjpc/tasks/CMakeLists.txt

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,21 @@ add_custom_target(
6060
COMMAND ${CMAKE_COMMAND} -E copy_directory
6161
${menagerie_SOURCE_DIR}/shadow_hand/assets
6262
${CMAKE_CURRENT_BINARY_DIR}/cube/assets
63+
64+
# ALOHA
65+
COMMAND ${CMAKE_COMMAND} -E copy_directory
66+
${menagerie_SOURCE_DIR}/aloha/assets
67+
${CMAKE_CURRENT_BINARY_DIR}/bimanual/assets
68+
COMMAND ${CMAKE_COMMAND} -E copy
69+
${menagerie_SOURCE_DIR}/aloha/aloha.xml
70+
${CMAKE_CURRENT_BINARY_DIR}/bimanual/aloha.xml
71+
COMMAND ${CMAKE_COMMAND} -E copy
72+
${menagerie_SOURCE_DIR}/aloha/integrated_cartesian_actuators.xml
73+
${CMAKE_CURRENT_BINARY_DIR}/bimanual/integrated_cartesian_actuators.xml
74+
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/bimanual/aloha.xml
75+
${CMAKE_CURRENT_BINARY_DIR}/bimanual/aloha.xml
76+
<${CMAKE_CURRENT_SOURCE_DIR}/bimanual/aloha.patch
77+
6378
COMMAND ${CMAKE_COMMAND} -E copy
6479
${menagerie_SOURCE_DIR}/robotis_op3/op3.xml
6580
${CMAKE_CURRENT_BINARY_DIR}/op3/op3.xml
@@ -69,6 +84,7 @@ add_custom_target(
6984
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/op3/op3_modified.xml
7085
${CMAKE_CURRENT_BINARY_DIR}/op3/op3.xml
7186
<${CMAKE_CURRENT_SOURCE_DIR}/op3/op3.xml.patch
87+
7288
COMMAND ${Python_EXECUTABLE}
7389
${CMAKE_CURRENT_BINARY_DIR}/manipulation/merge_panda_robotiq.py
7490
${CMAKE_CURRENT_BINARY_DIR}/manipulation/panda_robotiq.xml

mjpc/tasks/bimanual/aloha.patch

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
diff --git a/aloha.xml b/aloha.xml
2+
--- a/aloha.xml
3+
+++ b/aloha.xml
4+
@@ -284,5 +285,5 @@
5+
<joint joint1="right/left_finger" joint2="right/right_finger" polycoef="0 1 0 0 0"/>
6+
</equality>
7+
8+
- <include file="joint_position_actuators.xml"/>
9+
+ <include file="integrated_cartesian_actuators.xml"/>
10+
</mujoco>

mjpc/tasks/bimanual/bimanual.cc

Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
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/bimanual.h"
16+
17+
#include <string>
18+
19+
#include <mujoco/mujoco.h>
20+
#include "mjpc/utilities.h"
21+
22+
namespace mjpc {
23+
std::string Bimanual::XmlPath() const {
24+
return GetModelPath("bimanual/task.xml");
25+
}
26+
std::string Bimanual::Name() const { return "Bimanual"; }
27+
28+
void Bimanual::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+
CheckSensorDim(model, counter);
48+
}
49+
50+
void mjpc::Bimanual::TransitionLocked(mjModel* model, mjData* data) {
51+
data->mocap_pos[0] = -0.4;
52+
data->mocap_pos[1] = -0.2;
53+
data->mocap_pos[2] = 0.3;
54+
}
55+
56+
} // namespace mjpc

mjpc/tasks/bimanual/bimanual.h

Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
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_BIMANUAL_H_
16+
#define MJPC_MJPC_TASKS_BIMANUAL_BIMANUAL_H_
17+
18+
#include <memory>
19+
#include <string>
20+
21+
#include <mujoco/mujoco.h>
22+
#include "mjpc/task.h"
23+
24+
namespace mjpc {
25+
class Bimanual : 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 Bimanual* task) : BaseResidualFn(task) {}
33+
void Residual(const mjModel* model, const mjData* data,
34+
double* residual) const override;
35+
};
36+
37+
Bimanual() : residual_(this) {}
38+
void TransitionLocked(mjModel* model, mjData* data) override;
39+
40+
protected:
41+
std::unique_ptr<mjpc::ResidualFn> ResidualLocked() const override {
42+
return std::make_unique<ResidualFn>(this);
43+
}
44+
ResidualFn* InternalResidual() override { return &residual_; }
45+
46+
private:
47+
ResidualFn residual_;
48+
};
49+
} // namespace mjpc
50+
51+
52+
#endif // MJPC_MJPC_TASKS_BIMANUAL_BIMANUAL_H_

mjpc/tasks/bimanual/task.xml

Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
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="100"/>
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+
<include file="aloha_cartesian.xml"/>
32+
33+
<worldbody>
34+
<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"
35+
directional="true" castshadow="true"/>
36+
<geom name="floor" pos="0 0 -0.75" size="0 0 0.05" type="plane" material="groundplane"/>
37+
<body name="table" pos="0 0 -0.75">
38+
<geom name="table" pos="0 0 0.6509" size="0.61 0.37 0.1" type="box" class="collision"/>
39+
</body>
40+
<body mocap="true" name="box_goal_mocap">
41+
<geom group="5" size="0.02" rgba="1 0.4 0.4 1" conaffinity="0" contype="0"/>
42+
</body>
43+
<body name="box">
44+
<freejoint/>
45+
<geom name="box" type="box" size="0.025 0.025 0.025" priority="1" condim="6"
46+
friction="1.5 .03 .003" rgba="0 1 0 1"/>
47+
</body>
48+
</worldbody>
49+
<keyframe>
50+
<key name="home" qpos=
51+
"0 -0.96 1.16 0 -0.3 0 0.002 0.002
52+
0 -0.96 1.16 0 -0.3 0 0.002 0.002
53+
0.1 0.2 0.3 1 0 0 0"
54+
act ="-0.1 0 0 0 0 0 0.01 0.1 0 0 0 0 0 0.01"
55+
ctrl="-0.1 0 0 0 0 0 0.01 0.1 0 0 0 0 0 0.01"/>
56+
</keyframe>
57+
58+
<sensor>
59+
<user name="Reach L" dim="3" user="2 0.1 0 5 0.01"/>
60+
<user name="Reach R" dim="3" user="2 0.1 0 5 0.01"/>
61+
<user name="Bring" dim="3" user="2 1 0 1 0.003"/>
62+
<!-- <user name="arm_table_contact" dim="2" user="2 0.5 0 1 0.01"/>
63+
<user name="arm_arm_contact" dim="1" user="2 0.5 0 1 0.01"/> -->
64+
<framepos name="left/gripper" objtype="site" objname="left/gripper"/>
65+
<framepos name="right/gripper" objtype="site" objname="right/gripper"/>
66+
<framepos name="box" objtype="body" objname="box"/>
67+
<framepos name="target" objtype="body" objname="box_goal_mocap"/>
68+
<framepos name="trace0" objtype="site" objname="left/gripper"/>
69+
<framepos name="trace1" objtype="site" objname="right/gripper"/>
70+
71+
72+
</sensor>
73+
</mujoco>

mjpc/tasks/tasks.cc

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
#include "mjpc/task.h"
2121
#include "mjpc/tasks/acrobot/acrobot.h"
22+
#include "mjpc/tasks/bimanual/bimanual.h"
2223
#include "mjpc/tasks/cube/solve.h"
2324
#include "mjpc/tasks/cartpole/cartpole.h"
2425
#include "mjpc/tasks/fingers/fingers.h"
@@ -41,6 +42,7 @@ namespace mjpc {
4142
std::vector<std::shared_ptr<Task>> GetTasks() {
4243
return {
4344
std::make_shared<Acrobot>(),
45+
std::make_shared<Bimanual>(),
4446
std::make_shared<CubeSolve>(),
4547
std::make_shared<Cartpole>(),
4648
std::make_shared<Fingers>(),

0 commit comments

Comments
 (0)