|
| 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 |
0 commit comments