Skip to content

Commit 744912d

Browse files
authored
Merge pull request #251 from thowell/op3
OP3 task
2 parents 977630e + 7b1e403 commit 744912d

File tree

8 files changed

+368
-1
lines changed

8 files changed

+368
-1
lines changed

mjpc/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,8 @@ add_library(
5454
tasks/manipulation/common.h
5555
tasks/manipulation/manipulation.cc
5656
tasks/manipulation/manipulation.h
57+
tasks/op3/stand.cc
58+
tasks/op3/stand.h
5759
tasks/panda/panda.cc
5860
tasks/panda/panda.h
5961
tasks/particle/particle.cc

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(), 6); // start with manipulation bring
50+
mjpc::StartApp(mjpc::GetTasks(), 13); // start with quadruped flat
5151
return 0;
5252
}

mjpc/tasks/CMakeLists.txt

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,15 @@ add_custom_target(
3535
COMMAND ${CMAKE_COMMAND} -E copy_directory
3636
${menagerie_SOURCE_DIR}/skydio_x2/assets
3737
${CMAKE_CURRENT_BINARY_DIR}/quadrotor/assets
38+
COMMAND ${CMAKE_COMMAND} -E copy
39+
${menagerie_SOURCE_DIR}/robotis_op3/op3.xml
40+
${CMAKE_CURRENT_BINARY_DIR}/op3/op3.xml
41+
COMMAND ${CMAKE_COMMAND} -E copy_directory
42+
${menagerie_SOURCE_DIR}/robotis_op3/assets
43+
${CMAKE_CURRENT_BINARY_DIR}/op3/assets
44+
COMMAND patch -o ${CMAKE_CURRENT_BINARY_DIR}/op3/op3_modified.xml
45+
${CMAKE_CURRENT_BINARY_DIR}/op3/op3.xml
46+
<${CMAKE_CURRENT_SOURCE_DIR}/op3/op3.xml.patch
3847
COMMAND ${Python_EXECUTABLE}
3948
${CMAKE_CURRENT_BINARY_DIR}/manipulation/merge_panda_robotiq.py
4049
${CMAKE_CURRENT_BINARY_DIR}/manipulation/panda_robotiq.xml

mjpc/tasks/op3/op3.xml.patch

Lines changed: 69 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,69 @@
1+
diff --git a/op3_modified.xml b/op3_modified.xml
2+
--- a/op3_modified.xml
3+
+++ b/op3_modified.xml
4+
@@ -72,6 +72,7 @@
5+
</default>
6+
7+
<worldbody>
8+
+ <geom name="floor" size="0 0 0.05" type="plane" material="blue_grid"/>
9+
<light name="spotlight" mode="targetbodycom" target="body_link" pos="0 -1 2"/>
10+
<body name="body_link" pos="0 0 0.3">
11+
<inertial pos="-0.01501 0.00013 0.06582" quat="0.704708 0.704003 0.0667707 -0.0575246" mass="1.34928"
12+
@@ -87,13 +88,14 @@
13+
<body name="head_pan_link" pos="-0.001 0 0.1365">
14+
<inertial pos="0.00233 0 0.00823" quat="0.663575 0.663575 0.244272 -0.244272" mass="0.01176"
15+
diaginertia="4.23401e-06 3.60599e-06 1.65e-06"/>
16+
- <joint name="head_pan" axis="0 0 1"/>
17+
+ <!-- <joint name="head_pan" axis="0 0 1"/> -->
18+
<geom mesh="h1" class="visual"/>
19+
<geom mesh="h1c" class="collision"/>
20+
+ <site name="head" rgba="1 0 0 1" group="5"/>
21+
<body name="head_tilt_link" pos="0.01 0.019 0.0285">
22+
<inertial pos="0.0023 -0.01863 0.0277" quat="0.997312 0.00973825 0.0726131 -0.00102702" mass="0.13631"
23+
diaginertia="0.000107452 8.72266e-05 4.39413e-05"/>
24+
- <joint name="head_tilt" axis="0 -1 0"/>
25+
+ <!-- <joint name="head_tilt" axis="0 -1 0"/> -->
26+
<geom mesh="h2" class="visual"/>
27+
<geom mesh="h2c" class="collision"/>
28+
<geom mesh="h21c" class="collision"/>
29+
@@ -120,6 +122,7 @@
30+
<joint name="l_el" axis="1 0 0"/>
31+
<geom mesh="la3" class="visual"/>
32+
<geom mesh="la3c" class="collision"/>
33+
+ <site name="left_hand" rgba="1 0 0 1" pos="-0.02 0.14 0" group="5"/>
34+
</body>
35+
</body>
36+
</body>
37+
@@ -141,6 +144,7 @@
38+
<joint name="r_el" axis="1 0 0"/>
39+
<geom mesh="ra3" class="visual"/>
40+
<geom mesh="ra3c" class="collision"/>
41+
+ <site name="right_hand" rgba="1 0 0 1" pos="-0.02 -0.14 0" group="5"/>
42+
</body>
43+
</body>
44+
</body>
45+
@@ -181,6 +185,7 @@
46+
<!-- <geom mesh="ll6c" class="collision" /> -->
47+
<geom class="foot" pos="0.024 0.013 -0.0265" size="0.0635 0.028 0.004"/>
48+
<geom class="foot" pos="0.024 0.0125 -0.0265" size="0.057 0.039 0.004"/>
49+
+ <site name="left_foot" rgba="1 0 0 1" pos="0.025 0 -0.025" group="5"/>
50+
</body>
51+
</body>
52+
</body>
53+
@@ -224,6 +229,7 @@
54+
<!-- <geom mesh="rl6c" class="collision" /> -->
55+
<geom class="foot" pos="0.024 -0.013 -0.0265" size="0.0635 0.028 0.004"/>
56+
<geom class="foot" pos="0.024 -0.0125 -0.0265" size="0.057 0.039 0.004"/>
57+
+ <site name="right_foot" rgba="1 0 0 1" pos="0.025 0 -0.025" group="5"/>
58+
</body>
59+
</body>
60+
</body>
61+
@@ -239,8 +245,6 @@
62+
</contact>
63+
64+
<actuator>
65+
- <position name="head_pan_act" joint="head_pan"/>
66+
- <position name="head_tilt_act" joint="head_tilt"/>
67+
<position name="l_sho_pitch_act" joint="l_sho_pitch"/>
68+
<position name="l_sho_roll_act" joint="l_sho_roll"/>
69+
<position name="l_el_act" joint="l_el"/>

mjpc/tasks/op3/stand.cc

Lines changed: 166 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,166 @@
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/op3/stand.h"
16+
17+
#include <string>
18+
19+
#include <mujoco/mujoco.h>
20+
#include "mjpc/task.h"
21+
#include "mjpc/utilities.h"
22+
23+
namespace mjpc {
24+
std::string OP3::XmlPath() const { return GetModelPath("OP3/task.xml"); }
25+
std::string OP3::Name() const { return "OP3"; }
26+
27+
// ------- Residuals for OP3 task ------------
28+
// Residual(0): height - feet height
29+
// Residual(1): balance
30+
// Residual(2): center of mass xy velocity
31+
// Residual(3): ctrl - ctrl_nominal
32+
// Residual(4): upright
33+
// Residual(5): joint velocity
34+
// -------------------------------------------
35+
void OP3::ResidualFn::Residual(const mjModel* model, const mjData* data,
36+
double* residual) const {
37+
// start counter
38+
int counter = 0;
39+
40+
// get mode
41+
int mode = current_mode_;
42+
43+
// ----- sensors ------ //
44+
double* head_position = SensorByName(model, data, "head_position");
45+
double* left_foot_position = SensorByName(model, data, "left_foot_position");
46+
double* right_foot_position =
47+
SensorByName(model, data, "right_foot_position");
48+
double* left_hand_position = SensorByName(model, data, "left_hand_position");
49+
double* right_hand_position =
50+
SensorByName(model, data, "right_hand_position");
51+
double* torso_up = SensorByName(model, data, "torso_up");
52+
double* hand_right_up = SensorByName(model, data, "hand_right_up");
53+
double* hand_left_up = SensorByName(model, data, "hand_left_up");
54+
double* foot_right_up = SensorByName(model, data, "foot_right_up");
55+
double* foot_left_up = SensorByName(model, data, "foot_left_up");
56+
double* com_position = SensorByName(model, data, "body_subtreecom");
57+
double* com_velocity = SensorByName(model, data, "body_subtreelinvel");
58+
59+
// ----- Height ----- //
60+
if (mode == kModeStand) {
61+
double head_feet_error = head_position[2] - 0.5 * (left_foot_position[2] +
62+
right_foot_position[2]);
63+
residual[counter++] = head_feet_error - parameters_[0];
64+
} else if (mode == kModeHandstand) {
65+
double hand_feet_error =
66+
0.5 * (left_foot_position[2] + right_foot_position[2]) -
67+
0.5 * (left_hand_position[2] - right_hand_position[2]);
68+
residual[counter++] = hand_feet_error - parameters_[0];
69+
}
70+
71+
// ----- Balance: CoM-feet xy error ----- //
72+
73+
// capture point
74+
double kFallTime = 0.05;
75+
double capture_point[3] = {com_position[0], com_position[1], com_position[2]};
76+
mju_addToScl3(capture_point, com_velocity, kFallTime);
77+
78+
// average feet xy position
79+
double fxy_avg[2] = {0.0};
80+
if (mode == kModeStand) {
81+
mju_addTo(fxy_avg, left_foot_position, 2);
82+
mju_addTo(fxy_avg, right_foot_position, 2);
83+
} else if (mode == kModeHandstand) {
84+
mju_addTo(fxy_avg, left_hand_position, 2);
85+
mju_addTo(fxy_avg, right_hand_position, 2);
86+
}
87+
88+
mju_scl(fxy_avg, fxy_avg, 0.5, 2);
89+
mju_subFrom(fxy_avg, capture_point, 2);
90+
double com_feet_distance = mju_norm(fxy_avg, 2);
91+
residual[counter++] = com_feet_distance;
92+
93+
// ----- COM xy velocity should be 0 ----- //
94+
mju_copy(&residual[counter], com_velocity, 2);
95+
counter += 2;
96+
97+
// ----- Ctrl difference ----- //
98+
mju_sub(residual + counter, data->ctrl,
99+
model->key_qpos + model->nq * mode + 7, model->nu);
100+
counter += model->nu;
101+
102+
// ----- Upright ----- //
103+
double standing = 1.0;
104+
double z_ref[3] = {0.0, 0.0, 1.0};
105+
106+
if (mode == kModeStand) {
107+
// right foot
108+
mju_sub3(&residual[counter], foot_right_up, z_ref);
109+
mju_scl3(&residual[counter], &residual[counter], 0.1 * standing);
110+
counter += 3;
111+
112+
mju_sub3(&residual[counter], foot_left_up, z_ref);
113+
mju_scl3(&residual[counter], &residual[counter], 0.1 * standing);
114+
counter += 3;
115+
116+
// torso
117+
residual[counter++] = torso_up[2] - 1.0;
118+
119+
// zero remaining residual
120+
mju_zero(residual + counter, 6);
121+
counter += 6;
122+
} else if (mode == kModeHandstand) {
123+
// right hand
124+
mju_sub3(&residual[counter], hand_right_up, z_ref);
125+
mju_scl3(&residual[counter], &residual[counter], 0.1 * standing);
126+
counter += 3;
127+
128+
// left hand
129+
mju_add3(&residual[counter], hand_left_up, z_ref);
130+
mju_scl3(&residual[counter], &residual[counter], 0.1 * standing);
131+
counter += 3;
132+
133+
// right foot
134+
mju_add3(&residual[counter], foot_right_up, z_ref);
135+
mju_scl3(&residual[counter], &residual[counter], 0.1 * standing);
136+
counter += 3;
137+
138+
// left foot
139+
mju_add3(&residual[counter], foot_left_up, z_ref);
140+
mju_scl3(&residual[counter], &residual[counter], 0.1 * standing);
141+
counter += 3;
142+
143+
// torso
144+
residual[counter++] = 1.0 * (torso_up[2] + 1.0);
145+
}
146+
147+
// ----- Joint velocity ----- //
148+
mju_copy(residual + counter, data->qvel + 6, model->nv - 6);
149+
counter += model->nv - 6;
150+
151+
// sensor dim sanity check
152+
CheckSensorDim(model, counter);
153+
}
154+
155+
void OP3::TransitionLocked(mjModel* model, mjData* d) {
156+
// check for mode change
157+
if (residual_.current_mode_ != mode) {
158+
// update mode for residual
159+
residual_.current_mode_ = mode;
160+
161+
// set height goal based on mode (stand, handstand)
162+
parameters[0] = kModeHeight[mode];
163+
}
164+
}
165+
166+
} // namespace mjpc

mjpc/tasks/op3/stand.h

Lines changed: 75 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,75 @@
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_OP3_STAND_H_
16+
#define MJPC_TASKS_OP3_STAND_H_
17+
18+
#include <memory>
19+
#include <string>
20+
21+
#include <mujoco/mujoco.h>
22+
#include "mjpc/task.h"
23+
24+
namespace mjpc {
25+
26+
class OP3 : public Task {
27+
public:
28+
std::string Name() const override;
29+
std::string XmlPath() const override;
30+
31+
class ResidualFn : public BaseResidualFn {
32+
public:
33+
explicit ResidualFn(const OP3* task, int current_mode = 0)
34+
: BaseResidualFn(task), current_mode_(current_mode) {}
35+
// ------- Residuals for OP3 task ------------
36+
// Residual(0): height - feet height
37+
// Residual(1): balance
38+
// Residual(2): center of mass xy velocity
39+
// Residual(3): ctrl - ctrl_nominal
40+
// Residual(4): upright
41+
// Residual(5): joint velocity
42+
// -------------------------------------------
43+
void Residual(const mjModel* model, const mjData* data,
44+
double* residual) const override;
45+
46+
private:
47+
friend class OP3;
48+
int current_mode_;
49+
50+
// modes
51+
enum OP3Mode {
52+
kModeStand = 0,
53+
kModeHandstand,
54+
};
55+
};
56+
57+
OP3() : residual_(this) {}
58+
void TransitionLocked(mjModel* model, mjData* data) override;
59+
60+
// default height goals
61+
constexpr static double kModeHeight[2] = {0.38, 0.57};
62+
63+
protected:
64+
std::unique_ptr<mjpc::ResidualFn> ResidualLocked() const override {
65+
return std::make_unique<ResidualFn>(this, residual_.current_mode_);
66+
}
67+
ResidualFn* InternalResidual() override { return &residual_; }
68+
69+
private:
70+
ResidualFn residual_;
71+
};
72+
73+
} // namespace mjpc
74+
75+
#endif // MJPC_TASKS_OP3_STAND_H_

mjpc/tasks/op3/task.xml

Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
<mujoco model="OP3 Get Up">
2+
<include file="../common.xml"/>
3+
<!-- modified from https://github.com/google-deepmind/mujoco_menagerie/tree/main/robotis_op3 -->
4+
<include file="op3_modified.xml" />
5+
<size memory="400K"/>
6+
7+
<custom>
8+
<numeric name="agent_planner" data="0" />
9+
<numeric name="agent_horizon" data="0.35" />
10+
<numeric name="agent_timestep" data="0.015" />
11+
<numeric name="sampling_trajectories" data="20"/>
12+
<numeric name="sampling_spline_points" data="3" />
13+
<numeric name="sampling_exploration" data="0.1" />
14+
<numeric name="gradient_spline_points" data="5" />
15+
<numeric name="residual_Height Goal" data="0.38 0.0 0.75" />
16+
<text name="task_transition" data="Stand|Handstand" />
17+
</custom>
18+
19+
<sensor>
20+
<user name="Height" dim="1" user="6 100.0 0.0 100.0 0.1" />
21+
<user name="Balance" dim="1" user="6 50.0 0.0 100.0 0.1" />
22+
<user name="CoM Vel." dim="2" user="0 10.0 0.0 100.0" />
23+
<user name="Ctrl Diff" dim="18" user="0 0.25 0.0 1.0" />
24+
<user name="Upright" dim="13" user="2 5.0 0.0 25.0 0.01" />
25+
<user name="Joint Vel" dim="18" user="0 1.0e-5 0 1.0e-3" />
26+
<framepos name="head_position" objtype="site" objname="head"/>
27+
<framepos name="left_foot_position" objtype="site" objname="left_foot"/>
28+
<framepos name="right_foot_position" objtype="site" objname="right_foot"/>
29+
<subtreelinvel name="body_subtreelinvel" body="body_link"/>
30+
<subtreecom name="body_subtreecom" body="body_link"/>
31+
<framezaxis name="torso_up" objtype="site" objname="torso"/>
32+
<framezaxis name="foot_right_up" objtype="site" objname="right_foot"/>
33+
<framezaxis name="foot_left_up" objtype="site" objname="left_foot"/>
34+
<framepos name="left_hand_position" objtype="site" objname="left_hand"/>
35+
<framepos name="right_hand_position" objtype="site" objname="right_hand"/>
36+
<frameyaxis name="hand_right_up" objtype="site" objname="right_hand"/>
37+
<frameyaxis name="hand_left_up" objtype="site" objname="left_hand"/>
38+
</sensor>
39+
40+
<keyframe>
41+
<key name='home' qpos='-0.00363268 -6.3448e-07 0.246 1 0 0 0 -0.534072 0.879648 -0.62832 0.534072 -0.879648 0.62832 1.93442e-05 -6.23496e-05 -0.596904 1.13098 0.534072 0 -1.80695e-05 6.15245e-05 0.596904 -1.13098 -0.534072 4.91532e-06'/>
42+
<key name='handstand' qpos='-0.00363268 -6.3448e-07 0.338 0 1 0 0 3.1416 0.879648 -0.62832 -3.1416 -0.879648 0.62832 1.93442e-05 -6.23496e-05 -0.596904 1.13098 0.534072 0 -1.80695e-05 6.15245e-05 0.596904 -1.13098 -0.534072 4.91532e-06'/>
43+
</keyframe>
44+
</mujoco>

0 commit comments

Comments
 (0)