Skip to content

Commit

Permalink
Merge deepmind branch into main
Browse files Browse the repository at this point in the history
Merge deepmind branch into main
  • Loading branch information
erez-tom authored Feb 23, 2024
2 parents 42eef44 + 063ff93 commit 50a0159
Show file tree
Hide file tree
Showing 12 changed files with 259 additions and 27 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ set(MUJOCO_BUILD_TESTS OFF)
set(MUJOCO_TEST_PYTHON_UTIL OFF)

set(MUJOCO_MPC_MUJOCO_GIT_TAG
3.1.1
24eb4c9f092da7dd245a116841a5325a0fb359b9
CACHE STRING "Git revision for MuJoCo."
)

Expand Down
6 changes: 4 additions & 2 deletions mjpc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,10 @@ add_library(
tasks/acrobot/acrobot.h
tasks/allegro/allegro.cc
tasks/allegro/allegro.h
tasks/bimanual/bimanual.cc
tasks/bimanual/bimanual.h
tasks/bimanual/handover/handover.cc
tasks/bimanual/handover/handover.h
tasks/bimanual/reorient/reorient.cc
tasks/bimanual/reorient/reorient.h
tasks/cartpole/cartpole.cc
tasks/cartpole/cartpole.h
tasks/fingers/fingers.cc
Expand Down
4 changes: 2 additions & 2 deletions mjpc/tasks/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -116,11 +116,11 @@ add_custom_target(
${CMAKE_CURRENT_BINARY_DIR}/quadrotor/quadrotor.xml
<${CMAKE_CURRENT_SOURCE_DIR}/quadrotor/quadrotor.xml.patch

## Cube reorientation
## Cube reorientation
# patch cube from common assets
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/common_assets/cube_modified_shadow_reorient.xml
${CMAKE_CURRENT_BINARY_DIR}/common_assets/reorientation_cube.xml
<${CMAKE_CURRENT_SOURCE_DIR}/shadow_reorient/cube.xml.patch
<${CMAKE_CURRENT_SOURCE_DIR}/common_assets/cube.xml.patch

## Cube solve task
# copy cube model from MuJoCo
Expand Down
37 changes: 37 additions & 0 deletions mjpc/tasks/bimanual/aloha.patch
Original file line number Diff line number Diff line change
@@ -1,6 +1,43 @@
diff --git a/aloha.xml b/aloha.xml
--- a/aloha.xml
+++ b/aloha.xml
@@ -1,23 +1,23 @@
<mujoco model="aloha">
- <compiler angle="radian" meshdir="assets" autolimits="true"/>
+ <compiler angle="radian" autolimits="true"/>

<option cone="elliptic" impratio="10"/>

<asset>
<material name="black" rgba="0.15 0.15 0.15 1"/>

- <mesh file="vx300s_1_base.stl" scale="0.001 0.001 0.001"/>
- <mesh file="vx300s_2_shoulder.stl" scale="0.001 0.001 0.001"/>
- <mesh file="vx300s_3_upper_arm.stl" scale="0.001 0.001 0.001"/>
- <mesh file="vx300s_4_upper_forearm.stl" scale="0.001 0.001 0.001"/>
- <mesh file="vx300s_5_lower_forearm.stl" scale="0.001 0.001 0.001"/>
- <mesh file="vx300s_6_wrist.stl" scale="0.001 0.001 0.001"/>
- <mesh file="vx300s_7_gripper_prop.stl"/>
- <mesh file="vx300s_7_gripper_bar.stl"/>
- <mesh file="vx300s_7_gripper_wrist_mount.stl"/>
- <mesh file="vx300s_8_custom_finger_left.stl"/>
- <mesh file="vx300s_8_custom_finger_right.stl"/>
- <mesh file="d405_solid.stl"/>
+ <mesh file="assets/vx300s_1_base.stl" scale="0.001 0.001 0.001"/>
+ <mesh file="assets/vx300s_2_shoulder.stl" scale="0.001 0.001 0.001"/>
+ <mesh file="assets/vx300s_3_upper_arm.stl" scale="0.001 0.001 0.001"/>
+ <mesh file="assets/vx300s_4_upper_forearm.stl" scale="0.001 0.001 0.001"/>
+ <mesh file="assets/vx300s_5_lower_forearm.stl" scale="0.001 0.001 0.001"/>
+ <mesh file="assets/vx300s_6_wrist.stl" scale="0.001 0.001 0.001"/>
+ <mesh file="assets/vx300s_7_gripper_prop.stl"/>
+ <mesh file="assets/vx300s_7_gripper_bar.stl"/>
+ <mesh file="assets/vx300s_7_gripper_wrist_mount.stl"/>
+ <mesh file="assets/vx300s_8_custom_finger_left.stl"/>
+ <mesh file="assets/vx300s_8_custom_finger_right.stl"/>
+ <mesh file="assets/d405_solid.stl"/>
</asset>

<default>
@@ -284,5 +285,5 @@
<joint joint1="right/left_finger" joint2="right/right_finger" polycoef="0 1 0 0 0"/>
</equality>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,20 +12,20 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "mjpc/tasks/bimanual/bimanual.h"
#include "mjpc/tasks/bimanual/handover/handover.h"

#include <string>

#include <mujoco/mujoco.h>
#include "mjpc/utilities.h"

namespace mjpc {
std::string Bimanual::XmlPath() const {
return GetModelPath("bimanual/task.xml");
namespace mjpc::aloha {
std::string Handover::XmlPath() const {
return GetModelPath("bimanual/handover/task.xml");
}
std::string Bimanual::Name() const { return "Bimanual"; }
std::string Handover::Name() const { return "Bimanual Handover"; }

void Bimanual::ResidualFn::Residual(const mjModel* model, const mjData* data,
void Handover::ResidualFn::Residual(const mjModel* model, const mjData* data,
double* residual) const {
int counter = 0;

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

void mjpc::Bimanual::TransitionLocked(mjModel* model, mjData* data) {
}

} // namespace mjpc
} // namespace mjpc::aloha
Original file line number Diff line number Diff line change
Expand Up @@ -12,30 +12,29 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MJPC_MJPC_TASKS_BIMANUAL_BIMANUAL_H_
#define MJPC_MJPC_TASKS_BIMANUAL_BIMANUAL_H_
#ifndef MJPC_MJPC_TASKS_BIMANUAL_HANDOVER_HANDOVER_H_
#define MJPC_MJPC_TASKS_BIMANUAL_HANDOVER_HANDOVER_H_

#include <memory>
#include <string>

#include <mujoco/mujoco.h>
#include "mjpc/task.h"

namespace mjpc {
class Bimanual : public Task {
namespace mjpc::aloha {
class Handover : public Task {
public:
std::string Name() const override;
std::string XmlPath() const override;

class ResidualFn : public BaseResidualFn {
public:
explicit ResidualFn(const Bimanual* task) : BaseResidualFn(task) {}
explicit ResidualFn(const Handover* task) : BaseResidualFn(task) {}
void Residual(const mjModel* model, const mjData* data,
double* residual) const override;
};

Bimanual() : residual_(this) {}
void TransitionLocked(mjModel* model, mjData* data) override;
Handover() : residual_(this) {}

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


#endif // MJPC_MJPC_TASKS_BIMANUAL_BIMANUAL_H_
#endif // MJPC_MJPC_TASKS_BIMANUAL_HANDOVER_HANDOVER_H_
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<mujoco model="aloha">
<include file="../common.xml"/>
<include file="../../common.xml"/>

<size memory="1M"/>

Expand Down Expand Up @@ -28,7 +28,7 @@
<scale framelength=".3" framewidth=".03"/>
</visual>

<include file="aloha_cartesian.xml"/>
<include file="../aloha_cartesian.xml"/>

<worldbody>
<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"
Expand Down
66 changes: 66 additions & 0 deletions mjpc/tasks/bimanual/reorient/reorient.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
// 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/bimanual/reorient/reorient.h"

#include <string>

#include <mujoco/mujoco.h>
#include "mjpc/utilities.h"

namespace mjpc::aloha {
std::string Reorient::XmlPath() const {
return GetModelPath("bimanual/reorient/task.xml");
}
std::string Reorient::Name() const { return "Bimanual Reorient"; }

void Reorient::ResidualFn::Residual(const mjModel* model, const mjData* data,
double* residual) const {
int counter = 0;

// reach
double* left_gripper = SensorByName(model, data, "left/gripper");
double* box = SensorByName(model, data, "box");
mju_sub3(residual + counter, left_gripper, box);
counter += 3;

double* right_gripper = SensorByName(model, data, "right/gripper");
mju_sub3(residual + counter, right_gripper, box);
counter += 3;

// bring
double* target = SensorByName(model, data, "target");
mju_sub3(residual + counter, box, target);
counter += 3;

// ---------- Cube orientation ----------
double *cube_orientation = SensorByName(model, data, "cube_orientation");
double *goal_cube_orientation =
SensorByName(model, data, "cube_goal_orientation");
mju_normalize4(goal_cube_orientation);

mju_subQuat(residual + counter, goal_cube_orientation, cube_orientation);
counter += 3;

// ---------- Cube linear velocity ----------
double *cube_linear_velocity =
SensorByName(model, data, "cube_linear_velocity");

mju_copy(residual + counter, cube_linear_velocity, 3);
counter += 3;

CheckSensorDim(model, counter);
}

} // namespace mjpc::aloha
51 changes: 51 additions & 0 deletions mjpc/tasks/bimanual/reorient/reorient.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
// Copyright 2024 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_MJPC_TASKS_BIMANUAL_REORIENT_REORIENT_H_
#define MJPC_MJPC_TASKS_BIMANUAL_REORIENT_REORIENT_H_

#include <memory>
#include <string>

#include <mujoco/mujoco.h>
#include "mjpc/task.h"

namespace mjpc::aloha {
class Reorient : public Task {
public:
std::string Name() const override;
std::string XmlPath() const override;

class ResidualFn : public BaseResidualFn {
public:
explicit ResidualFn(const Reorient* task) : BaseResidualFn(task) {}
void Residual(const mjModel* model, const mjData* data,
double* residual) const override;
};

Reorient() : residual_(this) {}

protected:
std::unique_ptr<mjpc::ResidualFn> ResidualLocked() const override {
return std::make_unique<ResidualFn>(this);
}
ResidualFn* InternalResidual() override { return &residual_; }

private:
ResidualFn residual_;
};
} // namespace mjpc::aloha


#endif // MJPC_MJPC_TASKS_BIMANUAL_REORIENT_REORIENT_H_
78 changes: 78 additions & 0 deletions mjpc/tasks/bimanual/reorient/task.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
<mujoco model="aloha">
<include file="../../common.xml"/>

<size memory="1M"/>

<asset>
<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"/>
<material name="groundplane" texture="groundplane" texrepeat="2 2" texuniform="true" reflectance="0.20000000000000001"/>
</asset>

<custom>
<numeric name="agent_planner" data="0" />
<numeric name="agent_horizon" data="1.0" />
<numeric name="agent_timestep" data="0.01" />
<numeric name="agent_sample_width" data="0.0025" />
<numeric name="agent_policy_width" data="0.0035" />
<numeric name="sampling_exploration" data="0.5" />
<numeric name="sampling_trajectories" data="120"/>
<numeric name="sampling_spline_points" data="4" />
<numeric name="gradient_spline_points" data="6" />
</custom>

<statistic extent="1.5" center="0.0 0.35 0.2"/>

<visual>
<quality shadowsize="8192"/>
<global azimuth="90" elevation="-30"/>
<scale framelength=".3" framewidth=".03"/>
</visual>

<!-- since the included reorientation_cube brings its own sensors, the residuals must be specified first -->
<sensor>
<user name="Reach L" dim="3" user="2 0.1 0 .5 0.005"/>
<user name="Reach R" dim="3" user="2 0.1 0 .5 0.005"/>
<user name="Bring" dim="3" user="2 1 0 1 0.003"/>
<user name="Cube Orientation" dim="3" user="0 0.02 0 .2" />
<user name="Cube Velocity" dim="3" user="0 .01 0 .2" />
<framequat name="cube_goal_orientation" objtype="body" objname="goal"/>
<framepos name="left/gripper" objtype="site" objname="left/gripper"/>
<framepos name="right/gripper" objtype="site" objname="right/gripper"/>
<framepos name="box" objtype="body" objname="cube"/>
<framepos name="target" objtype="body" objname="box_goal_mocap"/>
<framepos name="trace0" objtype="body" objname="cube"/>
<framepos name="trace1" objtype="site" objname="left/gripper"/>
<framepos name="trace2" objtype="site" objname="right/gripper"/>
</sensor>

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

<worldbody>
<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"
directional="true" castshadow="true"/>
<geom name="floor" pos="0 0 -0.75" size="0 0 0.05" type="plane" material="groundplane"/>
<body name="table" pos="0 0 -0.75">
<geom name="table" pos="0 0 0.6509" size="0.61 0.37 0.1" type="box" class="collision"/>
<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"/>
</body>
<body mocap="true" name="box_goal_mocap">
<geom group="2" size="0.02" rgba="1 0.4 0.4 1" conaffinity="0" contype="0"/>
</body>
<body name="goal" pos="0.325 0.17 0.0475">
<joint type="ball" damping="0.001"/>
<geom type="box" size=".03 .03 .03" mass=".124" material="cube" contype="0" conaffinity="0"/>
</body>
</worldbody>
<keyframe>
<key name="home" qpos=
"0 -0.96 1.16 0 -0.3 0 0.002 0.002
0 -0.96 1.16 0 -0.3 0 0.002 0.002
0.02 0.02 0.075 1 0 0 0
1 0 0 0
"
mpos="0 0 0.25"
act= "-0.1 0 0 0 0 0 0.03 0.1 0 0 0 0 0 0.03"
ctrl="-0.1 0 0 0 0 0 0.03 0.1 0 0 0 0 0 0.03"/>
</keyframe>
</mujoco>
File renamed without changes.
6 changes: 4 additions & 2 deletions mjpc/tasks/tasks.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,8 @@
#include "mjpc/task.h"
#include "mjpc/tasks/acrobot/acrobot.h"
#include "mjpc/tasks/allegro/allegro.h"
#include "mjpc/tasks/bimanual/bimanual.h"
#include "mjpc/tasks/bimanual/handover/handover.h"
#include "mjpc/tasks/bimanual/reorient/reorient.h"
#include "mjpc/tasks/cartpole/cartpole.h"
#include "mjpc/tasks/fingers/fingers.h"
#include "mjpc/tasks/humanoid/stand/stand.h"
Expand All @@ -44,7 +45,8 @@ std::vector<std::shared_ptr<Task>> GetTasks() {
return {
std::make_shared<Acrobot>(),
std::make_shared<Allegro>(),
std::make_shared<Bimanual>(),
std::make_shared<aloha::Handover>(),
std::make_shared<aloha::Reorient>(),
std::make_shared<Cartpole>(),
std::make_shared<Fingers>(),
std::make_shared<humanoid::Stand>(),
Expand Down

0 comments on commit 50a0159

Please sign in to comment.