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