Skip to content

Commit 7476409

Browse files
authored
Merge pull request #243 from alberthli/albert/allegro-task-no-assets
Allegro Cube Rotation Task
2 parents fb069f1 + 3142873 commit 7476409

22 files changed

+357
-35
lines changed

mjpc/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@ add_library(
3838
tasks/tasks.h
3939
tasks/acrobot/acrobot.cc
4040
tasks/acrobot/acrobot.h
41+
tasks/allegro/allegro.cc
42+
tasks/allegro/allegro.h
4143
tasks/bimanual/bimanual.cc
4244
tasks/bimanual/bimanual.h
4345
tasks/cartpole/cartpole.cc

mjpc/spline/spline.h

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -15,16 +15,16 @@
1515
#ifndef MJPC_MJPC_SPLINE_SPLINE_H_
1616
#define MJPC_MJPC_SPLINE_SPLINE_H_
1717

18+
#include <absl/log/check.h>
19+
#include <absl/types/span.h>
20+
1821
#include <array>
1922
#include <cstddef>
2023
#include <deque>
2124
#include <iterator>
2225
#include <type_traits>
2326
#include <vector>
2427

25-
#include <absl/log/check.h>
26-
#include <absl/types/span.h>
27-
2828
namespace mjpc::spline {
2929

3030
enum SplineInterpolation : int {
@@ -33,7 +33,6 @@ enum SplineInterpolation : int {
3333
kCubicSpline,
3434
};
3535

36-
3736
// Represents a spline where values are interpolated based on time.
3837
// Allows updating the spline by adding new future points, or removing old
3938
// nodes.
@@ -56,7 +55,7 @@ class TimeSpline {
5655
template <typename T>
5756
class NodeT {
5857
public:
59-
NodeT() : time_(0) {};
58+
NodeT() : time_(0){};
6059
NodeT(double time, T* values, int dim)
6160
: time_(time), values_(values, dim) {}
6261

@@ -224,7 +223,6 @@ class TimeSpline {
224223
// Returns the number of nodes in the spline.
225224
std::size_t Size() const;
226225

227-
228226
// Returns the node at the given index, sorted by time. Any calls that mutate
229227
// the spline will invalidate the Node object.
230228
Node NodeAt(int index);

mjpc/tasks/CMakeLists.txt

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,15 @@
1717

1818
add_custom_target(
1919
copy_menagerie_resources ALL
20+
COMMAND ${CMAKE_COMMAND} -E copy
21+
${menagerie_SOURCE_DIR}/wonik_allegro/right_hand.xml
22+
${CMAKE_CURRENT_BINARY_DIR}/allegro/right_hand.xml
23+
COMMAND ${CMAKE_COMMAND} -E copy_directory
24+
${menagerie_SOURCE_DIR}/wonik_allegro/assets
25+
${CMAKE_CURRENT_BINARY_DIR}/allegro/assets
26+
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/allegro/right_hand_modified.xml
27+
${CMAKE_CURRENT_BINARY_DIR}/allegro/right_hand.xml
28+
<${CMAKE_CURRENT_SOURCE_DIR}/allegro/right_hand.xml.patch
2029
COMMAND ${CMAKE_COMMAND} -E copy_directory
2130
${menagerie_SOURCE_DIR}/shadow_hand/assets
2231
${CMAKE_CURRENT_BINARY_DIR}/hand/assets

mjpc/tasks/allegro/allegro.cc

Lines changed: 116 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,116 @@
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/allegro/allegro.h"
16+
17+
#include <mujoco/mujoco.h>
18+
19+
#include <cmath>
20+
#include <string>
21+
#include <vector>
22+
23+
#include "mjpc/task.h"
24+
#include "mjpc/utilities.h"
25+
26+
namespace mjpc {
27+
std::string Allegro::XmlPath() const {
28+
return GetModelPath("allegro/task.xml");
29+
}
30+
std::string Allegro::Name() const { return "Allegro"; }
31+
32+
// ------- Residuals for cube manipulation task ------
33+
// Cube position: (3)
34+
// Cube orientation: (3)
35+
// Cube linear velocity: (3)
36+
// Control: (16), there are 16 servos
37+
// Nominal pose: (16)
38+
// Joint velocity: (16)
39+
// ------------------------------------------
40+
void Allegro::ResidualFn::Residual(const mjModel *model, const mjData *data,
41+
double *residual) const {
42+
int counter = 0;
43+
44+
// ---------- Cube position ----------
45+
double *cube_position = SensorByName(model, data, "cube_position");
46+
double *cube_goal_position = SensorByName(model, data, "cube_goal_position");
47+
48+
mju_sub3(residual + counter, cube_position, cube_goal_position);
49+
counter += 3;
50+
51+
// ---------- Cube orientation ----------
52+
double *cube_orientation = SensorByName(model, data, "cube_orientation");
53+
double *goal_cube_orientation =
54+
SensorByName(model, data, "cube_goal_orientation");
55+
mju_normalize4(goal_cube_orientation);
56+
57+
mju_subQuat(residual + counter, goal_cube_orientation, cube_orientation);
58+
counter += 3;
59+
60+
// ---------- Cube linear velocity ----------
61+
double *cube_linear_velocity =
62+
SensorByName(model, data, "cube_linear_velocity");
63+
64+
mju_copy(residual + counter, cube_linear_velocity, 3);
65+
counter += 3;
66+
67+
// ---------- Control ----------
68+
mju_copy(residual + counter, data->actuator_force, model->nu);
69+
counter += model->nu;
70+
71+
// ---------- Nominal Pose ----------
72+
mju_sub(residual + counter, data->qpos + 7, model->key_qpos + 7, 16);
73+
counter += 16;
74+
75+
// ---------- Joint Velocity ----------
76+
mju_copy(residual + counter, data->qvel + 6, 16);
77+
counter += 16;
78+
79+
// Sanity check
80+
CheckSensorDim(model, counter);
81+
}
82+
83+
void Allegro::TransitionLocked(mjModel *model, mjData *data) {
84+
// Check for contact between the cube and the floor
85+
int cube = mj_name2id(model, mjOBJ_GEOM, "cube");
86+
int floor = mj_name2id(model, mjOBJ_GEOM, "floor");
87+
88+
bool on_floor = false;
89+
for (int i = 0; i < data->ncon; i++) {
90+
mjContact *g = data->contact + i;
91+
if ((g->geom1 == cube && g->geom2 == floor) ||
92+
(g->geom2 == cube && g->geom1 == floor)) {
93+
on_floor = true;
94+
break;
95+
}
96+
}
97+
98+
// If the cube is on the floor and not moving, reset it
99+
double *cube_lin_vel = SensorByName(model, data, "cube_linear_velocity");
100+
if (on_floor && mju_norm3(cube_lin_vel) < 0.001) {
101+
int cube_body = mj_name2id(model, mjOBJ_BODY, "cube");
102+
if (cube_body != -1) {
103+
int jnt_qposadr = model->jnt_qposadr[model->body_jntadr[cube_body]];
104+
int jnt_veladr = model->jnt_dofadr[model->body_jntadr[cube_body]];
105+
mju_copy(data->qpos + jnt_qposadr, model->qpos0 + jnt_qposadr, 7);
106+
mju_zero(data->qvel + jnt_veladr, 6);
107+
}
108+
109+
// Step the simulation forward
110+
mutex_.unlock();
111+
mj_forward(model, data);
112+
mutex_.lock();
113+
}
114+
}
115+
116+
} // namespace mjpc

mjpc/tasks/allegro/allegro.h

Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
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+
#ifndef MJPC_TASKS_ALLEGRO_ALLEGRO_H_
16+
#define MJPC_TASKS_ALLEGRO_ALLEGRO_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 Allegro : 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 Allegro *task) : BaseResidualFn(task) {}
33+
void Residual(const mjModel *model, const mjData *data,
34+
double *residual) const override;
35+
};
36+
Allegro() : residual_(this) {}
37+
38+
// Reset the cube into the hand if it's on the floor
39+
void TransitionLocked(mjModel *model, mjData *data) override;
40+
41+
protected:
42+
std::unique_ptr<mjpc::ResidualFn> ResidualLocked() const override {
43+
return std::make_unique<ResidualFn>(this);
44+
}
45+
ResidualFn *InternalResidual() override { return &residual_; }
46+
47+
private:
48+
ResidualFn residual_;
49+
};
50+
} // namespace mjpc
51+
52+
#endif // MJPC_TASKS_ALLEGRO_ALLEGRO_H_

mjpc/tasks/allegro/cube.xml

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
<mujoco>
2+
<asset>
3+
<texture name="cube" type="cube"
4+
fileup="../assets/cube/fileup.png" fileback="../assets/cube/fileback.png"
5+
filedown="../assets/cube/filedown.png" filefront="../assets/cube/filefront.png"
6+
fileleft="../assets/cube/fileleft.png" fileright="../assets/cube/fileright.png"/>
7+
<material name="cube" texture="cube"/>
8+
<texture name="graycube" type="cube" fileup="../assets/cube/grayup.png"
9+
fileback="../assets/cube/grayback.png" filedown="../assets/cube/graydown.png"
10+
filefront="../assets/cube/grayfront.png" fileleft="../assets/cube/grayleft.png"
11+
fileright="../assets/cube/grayright.png"/>
12+
<material name="graycube" texture="graycube"/>
13+
</asset>
14+
<worldbody>
15+
<light pos="0 0 1"/>
16+
<body name="cube" pos="0.2 0.0 0.075" quat="1 0 0 0">
17+
<freejoint/>
18+
<geom name="cube" type="box" size=".03 .03 .03" mass=".122" material="cube"/>
19+
</body>
20+
</worldbody>
21+
22+
<sensor>
23+
<framepos name="trace0" objtype="body" objname="cube"/>
24+
<framepos name="cube_position" objtype="body" objname="cube"/>
25+
<framequat name="cube_orientation" objtype="body" objname="cube"/>
26+
<framelinvel name="cube_linear_velocity" objtype="body" objname="cube"/>
27+
<frameangvel name="cube_angular_velocity" objtype="body" objname="cube"/>
28+
</sensor>
29+
</mujoco>
Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
diff --git a/right_hand_modified.xml b/right_hand_modified.xml
2+
--- a/right_hand_modified.xml
3+
+++ b/right_hand_modified.xml
4+
@@ -6,7 +6,7 @@
5+
<default>
6+
<default class="allegro_right">
7+
<joint axis="0 1 0" damping=".1"/>
8+
- <position kp="1"/>
9+
+ <position kp="0.5"/>
10+
<geom density="800"/>
11+
12+
<default class="visual">
13+
@@ -124,8 +124,9 @@
14+
</asset>
15+
16+
<worldbody>
17+
- <body name="palm" quat="0 1 0 1" childclass="allegro_right">
18+
+ <body name="palm" pos="0.25 0 0" quat="0 1 0 0.7" childclass="allegro_right">
19+
<!-- <inertial mass="0.4154" pos="0 0 0.0475" diaginertia="1e-4 1e-4 1e-4"/> -->
20+
+ <site name="grasp_site" pos="0.0 0.0 0.0" group="4"/>
21+
<geom class="palm_visual" mesh="base_link"/>
22+
<geom class="palm_collision"/>
23+
<!-- First finger -->
24+
@@ -148,6 +149,7 @@
25+
<body name="ff_tip">
26+
<geom class="fingertip_visual"/>
27+
<geom class="fingertip_collision"/>
28+
+ <site name="tip" pos="0 0 0"/>
29+
</body>
30+
</body>
31+
</body>
32+
@@ -257,4 +259,12 @@
33+
<position name="tha2" joint="thj2" class="thumb_medial"/>
34+
<position name="tha3" joint="thj3" class="thumb_distal"/>
35+
</actuator>
36+
+
37+
+ <!-- Traces for visualizing rollouts -->
38+
+ <sensor>
39+
+ <framepos name="trace1" objtype="body" objname="rf_tip"/>
40+
+ <framepos name="trace2" objtype="body" objname="ff_tip"/>
41+
+ <framepos name="trace3" objtype="body" objname="mf_tip"/>
42+
+ <framepos name="trace4" objtype="body" objname="th_tip"/>
43+
+ </sensor>
44+
</mujoco>

mjpc/tasks/allegro/task.xml

Lines changed: 70 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,70 @@
1+
<mujoco model="Allegro Hand Cube Rotation">
2+
<include file="../common.xml"/>
3+
4+
<size memory="1M"/>
5+
6+
<option integrator="implicitfast" iterations="100" ls_iterations="50"/>
7+
8+
<custom>
9+
<!-- agent -->
10+
<numeric name="agent_planner" data="0" />
11+
<numeric name="agent_horizon" data="0.5" />
12+
<numeric name="agent_timestep" data="0.01" />
13+
<numeric name="agent_policy_width" data="0.0035" />
14+
<numeric name="sampling_spline_points" data="6" />
15+
<numeric name="sampling_exploration" data="0.1" />
16+
<numeric name="sampling_trajectories" data="10" />
17+
<numeric name="sampling_representation" data="2" />
18+
<numeric name="robust_xfrc" data="0.004" />
19+
<numeric name="gradient_spline_points" data="6" />
20+
21+
<!-- cem -->
22+
<numeric name="n_elite" data="10" />
23+
<numeric name="std_min" data="0.2" />
24+
</custom>
25+
26+
<!-- Set the camera viewpoint -->
27+
<statistic extent="0.4" center="0.3 0.1 0"/>
28+
<visual>
29+
<quality shadowsize="8192"/>
30+
<global azimuth="180" elevation="-30"/>
31+
</visual>
32+
33+
<!-- Set default friction coefficient -->
34+
<default>
35+
<geom friction=".3"/>
36+
</default>
37+
38+
<!-- Create the scene, including floor and the interactive target cube. -->
39+
<worldbody>
40+
<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"
41+
directional="true" castshadow="true"/>
42+
<geom name="floor" pos="0 0 -0.2" size="0 0 0.05" type="plane" material="blue_grid"/>
43+
<body name="goal" pos="0.325 0.17 0.0475">
44+
<joint type="ball" damping="0.001"/>
45+
<geom type="box" size=".03 .03 .03" mass=".124" material="cube" contype="0" conaffinity="0"/>
46+
</body>
47+
</worldbody>
48+
49+
<sensor>
50+
<!-- Residuals -->
51+
<user name="Cube Position" dim="3" user="1 75 0 100 0.02 2"/>
52+
<user name="Cube Orientation" dim="3" user="0 7.5 0 10" />
53+
<user name="Cube Velocity" dim="3" user="0 10 0 20" />
54+
<user name="Actuation" dim="16" user="0 1 0.0 10" />
55+
<user name="Grasp" dim="16" user="0 0.1 0.0 10" />
56+
<user name="Joint Vel" dim="16" user="0 1.0e-3 0.0 0.1" />
57+
58+
<!-- Measurements we want to use -->
59+
<framepos name="cube_goal_position" objtype="site" objname="grasp_site"/>
60+
<framequat name="cube_goal_orientation" objtype="body" objname="goal"/>
61+
</sensor>
62+
63+
<include file="cube.xml"/>
64+
<!-- modified from: https://github.com/google-deepmind/mujoco_menagerie/tree/main/wonik_allegro -->
65+
<include file="right_hand_modified.xml"/>
66+
67+
<keyframe>
68+
<key name="home" qpos="1 0 0 0 0.2 0.025 0.075 1 0 0 0 0 0.58058 0.701595 0.538675 0 0.60767 0.758085 0.741625 0 0.8876 0.720425 0.5848 0.263 0.32612 1.08493 0.806715"/>
69+
</keyframe>
70+
</mujoco>
File renamed without changes.
File renamed without changes.

0 commit comments

Comments
 (0)