| Line |
Branch |
Exec |
Source |
| 1 |
|
|
// |
| 2 |
|
|
// Copyright (c) 2017 CNRS, NYU, MPI Tübingen |
| 3 |
|
|
// |
| 4 |
|
|
// This file is part of tsid |
| 5 |
|
|
// tsid is free software: you can redistribute it |
| 6 |
|
|
// and/or modify it under the terms of the GNU Lesser General Public |
| 7 |
|
|
// License as published by the Free Software Foundation, either version |
| 8 |
|
|
// 3 of the License, or (at your option) any later version. |
| 9 |
|
|
// tsid is distributed in the hope that it will be |
| 10 |
|
|
// useful, but WITHOUT ANY WARRANTY; without even the implied warranty |
| 11 |
|
|
// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU |
| 12 |
|
|
// General Lesser Public License for more details. You should have |
| 13 |
|
|
// received a copy of the GNU Lesser General Public License along with |
| 14 |
|
|
// tsid If not, see |
| 15 |
|
|
// <http://www.gnu.org/licenses/>. |
| 16 |
|
|
// |
| 17 |
|
|
|
| 18 |
|
|
#include "tsid/formulations/inverse-dynamics-formulation-acc-force.hpp" |
| 19 |
|
|
|
| 20 |
|
|
#include "tsid/math/constraint-bound.hpp" |
| 21 |
|
|
#include "tsid/math/constraint-inequality.hpp" |
| 22 |
|
|
|
| 23 |
|
|
using namespace tsid; |
| 24 |
|
|
using namespace math; |
| 25 |
|
|
using namespace tasks; |
| 26 |
|
|
using namespace contacts; |
| 27 |
|
|
using namespace solvers; |
| 28 |
|
|
using namespace std; |
| 29 |
|
|
|
| 30 |
|
|
typedef pinocchio::Data Data; |
| 31 |
|
|
|
| 32 |
|
✗ |
InverseDynamicsFormulationAccForce::InverseDynamicsFormulationAccForce( |
| 33 |
|
✗ |
const std::string &name, RobotWrapper &robot, bool verbose) |
| 34 |
|
|
: InverseDynamicsFormulationBase(name, robot, verbose), |
| 35 |
|
✗ |
m_data(robot.model()), |
| 36 |
|
✗ |
m_baseDynamics(new math::ConstraintEquality( |
| 37 |
|
✗ |
"base-dynamics", robot.nv() - robot.na(), robot.nv())), |
| 38 |
|
✗ |
m_solutionDecoded(false) { |
| 39 |
|
✗ |
m_t = 0.0; |
| 40 |
|
✗ |
m_v = robot.nv(); |
| 41 |
|
✗ |
m_u = robot.nv() - robot.na(); |
| 42 |
|
✗ |
m_k = 0; |
| 43 |
|
✗ |
m_eq = m_u; |
| 44 |
|
✗ |
m_in = 0; |
| 45 |
|
✗ |
m_hqpData.resize(2); |
| 46 |
|
✗ |
m_Jc.setZero(m_k, m_v); |
| 47 |
|
✗ |
h_fext.setZero(m_v); |
| 48 |
|
✗ |
m_hqpData[0].push_back( |
| 49 |
|
✗ |
solvers::make_pair<double, std::shared_ptr<ConstraintBase> >( |
| 50 |
|
✗ |
1.0, m_baseDynamics)); |
| 51 |
|
|
} |
| 52 |
|
|
|
| 53 |
|
✗ |
Data &InverseDynamicsFormulationAccForce::data() { return m_data; } |
| 54 |
|
|
|
| 55 |
|
✗ |
unsigned int InverseDynamicsFormulationAccForce::nVar() const { |
| 56 |
|
✗ |
return m_v + m_k; |
| 57 |
|
|
} |
| 58 |
|
|
|
| 59 |
|
✗ |
unsigned int InverseDynamicsFormulationAccForce::nEq() const { return m_eq; } |
| 60 |
|
|
|
| 61 |
|
✗ |
unsigned int InverseDynamicsFormulationAccForce::nIn() const { return m_in; } |
| 62 |
|
|
|
| 63 |
|
✗ |
void InverseDynamicsFormulationAccForce::resizeHqpData() { |
| 64 |
|
✗ |
m_Jc.setZero(m_k, m_v); |
| 65 |
|
✗ |
m_baseDynamics->resize(m_u, m_v + m_k); |
| 66 |
|
✗ |
for (HQPData::iterator it = m_hqpData.begin(); it != m_hqpData.end(); it++) { |
| 67 |
|
✗ |
for (ConstraintLevel::iterator itt = it->begin(); itt != it->end(); itt++) { |
| 68 |
|
✗ |
itt->second->resize(itt->second->rows(), m_v + m_k); |
| 69 |
|
|
} |
| 70 |
|
|
} |
| 71 |
|
|
} |
| 72 |
|
|
|
| 73 |
|
|
template <class TaskLevelPointer> |
| 74 |
|
✗ |
void InverseDynamicsFormulationAccForce::addTask(TaskLevelPointer tl, |
| 75 |
|
|
double weight, |
| 76 |
|
|
unsigned int priorityLevel) { |
| 77 |
|
✗ |
if (priorityLevel > m_hqpData.size()) m_hqpData.resize(priorityLevel); |
| 78 |
|
✗ |
const ConstraintBase &c = tl->task.getConstraint(); |
| 79 |
|
✗ |
if (c.isEquality()) { |
| 80 |
|
✗ |
tl->constraint = |
| 81 |
|
✗ |
std::make_shared<ConstraintEquality>(c.name(), c.rows(), m_v + m_k); |
| 82 |
|
✗ |
if (priorityLevel == 0) m_eq += c.rows(); |
| 83 |
|
|
} else // if(c.isInequality()) |
| 84 |
|
|
{ |
| 85 |
|
✗ |
tl->constraint = |
| 86 |
|
✗ |
std::make_shared<ConstraintInequality>(c.name(), c.rows(), m_v + m_k); |
| 87 |
|
✗ |
if (priorityLevel == 0) m_in += c.rows(); |
| 88 |
|
|
} |
| 89 |
|
|
// don't use bounds for now because EiQuadProg doesn't exploit them anyway |
| 90 |
|
|
// else |
| 91 |
|
|
// tl->constraint = new ConstraintBound(c.name(), m_v+m_k); |
| 92 |
|
✗ |
m_hqpData[priorityLevel].push_back( |
| 93 |
|
|
make_pair<double, std::shared_ptr<ConstraintBase> >(weight, |
| 94 |
|
✗ |
tl->constraint)); |
| 95 |
|
|
} |
| 96 |
|
|
|
| 97 |
|
✗ |
bool InverseDynamicsFormulationAccForce::addMotionTask( |
| 98 |
|
|
TaskMotion &task, double weight, unsigned int priorityLevel, |
| 99 |
|
|
double transition_duration) { |
| 100 |
|
✗ |
PINOCCHIO_CHECK_INPUT_ARGUMENT( |
| 101 |
|
|
weight >= 0.0, "The weight needs to be positive or equal to 0"); |
| 102 |
|
✗ |
PINOCCHIO_CHECK_INPUT_ARGUMENT( |
| 103 |
|
|
transition_duration >= 0.0, |
| 104 |
|
|
"The transition duration needs to be greater than or equal to 0"); |
| 105 |
|
|
|
| 106 |
|
✗ |
auto tl = std::make_shared<TaskLevel>(task, priorityLevel); |
| 107 |
|
✗ |
m_taskMotions.push_back(tl); |
| 108 |
|
✗ |
addTask(tl, weight, priorityLevel); |
| 109 |
|
|
|
| 110 |
|
✗ |
return true; |
| 111 |
|
|
} |
| 112 |
|
|
|
| 113 |
|
✗ |
bool InverseDynamicsFormulationAccForce::addForceTask( |
| 114 |
|
|
TaskContactForce &task, double weight, unsigned int priorityLevel, |
| 115 |
|
|
double transition_duration) { |
| 116 |
|
✗ |
PINOCCHIO_CHECK_INPUT_ARGUMENT( |
| 117 |
|
|
weight >= 0.0, "The weight needs to be positive or equal to 0"); |
| 118 |
|
✗ |
PINOCCHIO_CHECK_INPUT_ARGUMENT( |
| 119 |
|
|
transition_duration >= 0.0, |
| 120 |
|
|
"The transition duration needs to be greater than or equal to 0"); |
| 121 |
|
|
|
| 122 |
|
✗ |
auto tl = std::make_shared<TaskLevelForce>(task, priorityLevel); |
| 123 |
|
✗ |
m_taskContactForces.push_back(tl); |
| 124 |
|
✗ |
addTask(tl, weight, priorityLevel); |
| 125 |
|
✗ |
return true; |
| 126 |
|
|
} |
| 127 |
|
|
|
| 128 |
|
✗ |
bool InverseDynamicsFormulationAccForce::addActuationTask( |
| 129 |
|
|
TaskActuation &task, double weight, unsigned int priorityLevel, |
| 130 |
|
|
double transition_duration) { |
| 131 |
|
✗ |
PINOCCHIO_CHECK_INPUT_ARGUMENT( |
| 132 |
|
|
weight >= 0.0, "The weight needs to be positive or equal to 0"); |
| 133 |
|
✗ |
PINOCCHIO_CHECK_INPUT_ARGUMENT( |
| 134 |
|
|
transition_duration >= 0.0, |
| 135 |
|
|
"The transition duration needs to be greater than or equal to 0"); |
| 136 |
|
|
|
| 137 |
|
✗ |
auto tl = std::make_shared<TaskLevel>(task, priorityLevel); |
| 138 |
|
✗ |
m_taskActuations.push_back(tl); |
| 139 |
|
|
|
| 140 |
|
✗ |
if (priorityLevel > m_hqpData.size()) m_hqpData.resize(priorityLevel); |
| 141 |
|
|
|
| 142 |
|
✗ |
const ConstraintBase &c = tl->task.getConstraint(); |
| 143 |
|
✗ |
if (c.isEquality()) { |
| 144 |
|
✗ |
tl->constraint = |
| 145 |
|
✗ |
std::make_shared<ConstraintEquality>(c.name(), c.rows(), m_v + m_k); |
| 146 |
|
✗ |
if (priorityLevel == 0) m_eq += c.rows(); |
| 147 |
|
|
} else // an actuator bound becomes an inequality because actuator forces are |
| 148 |
|
|
// not in the problem variables |
| 149 |
|
|
{ |
| 150 |
|
✗ |
tl->constraint = |
| 151 |
|
✗ |
std::make_shared<ConstraintInequality>(c.name(), c.rows(), m_v + m_k); |
| 152 |
|
✗ |
if (priorityLevel == 0) m_in += c.rows(); |
| 153 |
|
|
} |
| 154 |
|
|
|
| 155 |
|
✗ |
m_hqpData[priorityLevel].push_back( |
| 156 |
|
✗ |
make_pair<double, std::shared_ptr<ConstraintBase> >(weight, |
| 157 |
|
✗ |
tl->constraint)); |
| 158 |
|
|
|
| 159 |
|
✗ |
return true; |
| 160 |
|
|
} |
| 161 |
|
|
|
| 162 |
|
✗ |
bool InverseDynamicsFormulationAccForce::updateTaskWeight( |
| 163 |
|
|
const std::string &task_name, double weight) { |
| 164 |
|
✗ |
ConstraintLevel::iterator it; |
| 165 |
|
|
// do not look into first priority level because weights do not matter there |
| 166 |
|
✗ |
for (unsigned int i = 1; i < m_hqpData.size(); i++) { |
| 167 |
|
✗ |
for (it = m_hqpData[i].begin(); it != m_hqpData[i].end(); it++) { |
| 168 |
|
✗ |
if (it->second->name() == task_name) { |
| 169 |
|
✗ |
it->first = weight; |
| 170 |
|
✗ |
return true; |
| 171 |
|
|
} |
| 172 |
|
|
} |
| 173 |
|
|
} |
| 174 |
|
✗ |
return false; |
| 175 |
|
|
} |
| 176 |
|
|
|
| 177 |
|
✗ |
bool InverseDynamicsFormulationAccForce::addRigidContact( |
| 178 |
|
|
ContactBase &contact, double force_regularization_weight, |
| 179 |
|
|
double motion_weight, unsigned int motionPriorityLevel) { |
| 180 |
|
✗ |
auto cl = std::make_shared<ContactLevel>(contact); |
| 181 |
|
✗ |
cl->index = m_k; |
| 182 |
|
✗ |
m_k += contact.n_force(); |
| 183 |
|
✗ |
m_contacts.push_back(cl); |
| 184 |
|
✗ |
resizeHqpData(); |
| 185 |
|
|
|
| 186 |
|
✗ |
const ConstraintBase &motionConstr = contact.getMotionConstraint(); |
| 187 |
|
✗ |
cl->motionConstraint = std::make_shared<ConstraintEquality>( |
| 188 |
|
✗ |
contact.name() + "_motion_task", motionConstr.rows(), m_v + m_k); |
| 189 |
|
✗ |
m_hqpData[motionPriorityLevel].push_back( |
| 190 |
|
✗ |
solvers::make_pair<double, std::shared_ptr<ConstraintBase> >( |
| 191 |
|
✗ |
motion_weight, cl->motionConstraint)); |
| 192 |
|
|
|
| 193 |
|
✗ |
const ConstraintInequality &forceConstr = contact.getForceConstraint(); |
| 194 |
|
✗ |
cl->forceConstraint = std::make_shared<ConstraintInequality>( |
| 195 |
|
✗ |
contact.name() + "_force_constraint", forceConstr.rows(), m_v + m_k); |
| 196 |
|
✗ |
m_hqpData[0].push_back( |
| 197 |
|
✗ |
solvers::make_pair<double, std::shared_ptr<ConstraintBase> >( |
| 198 |
|
✗ |
1.0, cl->forceConstraint)); |
| 199 |
|
|
|
| 200 |
|
|
const ConstraintEquality &forceRegConstr = |
| 201 |
|
✗ |
contact.getForceRegularizationTask(); |
| 202 |
|
✗ |
cl->forceRegTask = std::make_shared<ConstraintEquality>( |
| 203 |
|
✗ |
contact.name() + "_force_reg_task", forceRegConstr.rows(), m_v + m_k); |
| 204 |
|
✗ |
m_hqpData[1].push_back( |
| 205 |
|
✗ |
solvers::make_pair<double, std::shared_ptr<ConstraintBase> >( |
| 206 |
|
✗ |
force_regularization_weight, cl->forceRegTask)); |
| 207 |
|
|
|
| 208 |
|
✗ |
if (motionPriorityLevel == 0) m_eq += motionConstr.rows(); |
| 209 |
|
✗ |
m_in += forceConstr.rows(); |
| 210 |
|
|
|
| 211 |
|
✗ |
return true; |
| 212 |
|
|
} |
| 213 |
|
|
|
| 214 |
|
✗ |
bool InverseDynamicsFormulationAccForce::addRigidContact(ContactBase &contact) { |
| 215 |
|
|
std::cout << "[InverseDynamicsFormulationAccForce] Method " |
| 216 |
|
|
"addRigidContact(ContactBase) is deprecated. You should use " |
| 217 |
|
✗ |
"addRigidContact(ContactBase, double) instead.\n"; |
| 218 |
|
✗ |
return addRigidContact(contact, 1e-5); |
| 219 |
|
|
} |
| 220 |
|
|
|
| 221 |
|
✗ |
bool InverseDynamicsFormulationAccForce::updateRigidContactWeights( |
| 222 |
|
|
const std::string &contact_name, double force_regularization_weight, |
| 223 |
|
|
double motion_weight) { |
| 224 |
|
|
// update weight of force regularization task |
| 225 |
|
✗ |
ConstraintLevel::iterator itt; |
| 226 |
|
✗ |
bool force_reg_task_found = false; |
| 227 |
|
✗ |
bool motion_task_found = false; |
| 228 |
|
✗ |
for (unsigned int i = 1; i < m_hqpData.size(); i++) { |
| 229 |
|
✗ |
for (itt = m_hqpData[i].begin(); itt != m_hqpData[i].end(); itt++) { |
| 230 |
|
✗ |
if (itt->second->name() == contact_name + "_force_reg_task") { |
| 231 |
|
✗ |
if (force_regularization_weight >= 0.0) |
| 232 |
|
✗ |
itt->first = force_regularization_weight; |
| 233 |
|
✗ |
if (motion_task_found || motion_weight < 0.0) |
| 234 |
|
✗ |
return true; // If motion_weight is negative, the motion_task will |
| 235 |
|
|
// not be modified. The method can return here |
| 236 |
|
✗ |
force_reg_task_found = true; |
| 237 |
|
✗ |
} else if (itt->second->name() == contact_name + "_motion_task") { |
| 238 |
|
✗ |
if (motion_weight >= 0.0) itt->first = motion_weight; |
| 239 |
|
✗ |
if (force_reg_task_found) return true; |
| 240 |
|
✗ |
motion_task_found = true; |
| 241 |
|
|
} |
| 242 |
|
|
} |
| 243 |
|
|
} |
| 244 |
|
✗ |
return false; |
| 245 |
|
|
} |
| 246 |
|
|
|
| 247 |
|
✗ |
bool InverseDynamicsFormulationAccForce::addMeasuredForce( |
| 248 |
|
|
MeasuredForceBase &measuredForce) { |
| 249 |
|
✗ |
auto tl = std::make_shared<MeasuredForceLevel>(measuredForce); |
| 250 |
|
✗ |
m_measuredForces.push_back(tl); |
| 251 |
|
|
|
| 252 |
|
✗ |
return true; |
| 253 |
|
|
} |
| 254 |
|
|
|
| 255 |
|
✗ |
const HQPData &InverseDynamicsFormulationAccForce::computeProblemData( |
| 256 |
|
|
double time, ConstRefVector q, ConstRefVector v) { |
| 257 |
|
✗ |
m_t = time; |
| 258 |
|
|
|
| 259 |
|
✗ |
for (auto it_ct = m_contactTransitions.begin(); |
| 260 |
|
✗ |
it_ct != m_contactTransitions.end(); it_ct++) { |
| 261 |
|
✗ |
auto c = *it_ct; |
| 262 |
|
✗ |
assert(c->time_start <= m_t); |
| 263 |
|
✗ |
if (m_t <= c->time_end) { |
| 264 |
|
|
const double alpha = |
| 265 |
|
✗ |
(m_t - c->time_start) / (c->time_end - c->time_start); |
| 266 |
|
✗ |
const double fMax = c->fMax_start + alpha * (c->fMax_end - c->fMax_start); |
| 267 |
|
✗ |
c->contactLevel->contact.setMaxNormalForce(fMax); |
| 268 |
|
|
} else { |
| 269 |
|
|
// std::cout<<"[InverseDynamicsFormulationAccForce] Remove contact "<< |
| 270 |
|
|
// c->contactLevel->contact.name()<<" at time |
| 271 |
|
|
// "<<time<<std::endl; |
| 272 |
|
✗ |
removeRigidContact(c->contactLevel->contact.name()); |
| 273 |
|
|
// FIXME: this won't work if multiple contact transitions occur at the |
| 274 |
|
|
// same time because after erasing an element the iterator is invalid |
| 275 |
|
✗ |
m_contactTransitions.erase(it_ct); |
| 276 |
|
✗ |
break; |
| 277 |
|
|
} |
| 278 |
|
|
} |
| 279 |
|
|
|
| 280 |
|
✗ |
m_robot.computeAllTerms(m_data, q, v); |
| 281 |
|
|
|
| 282 |
|
✗ |
for (auto cl : m_contacts) { |
| 283 |
|
✗ |
unsigned int m = cl->contact.n_force(); |
| 284 |
|
|
|
| 285 |
|
|
const ConstraintBase &mc = |
| 286 |
|
✗ |
cl->contact.computeMotionTask(time, q, v, m_data); |
| 287 |
|
✗ |
cl->motionConstraint->matrix().leftCols(m_v) = mc.matrix(); |
| 288 |
|
✗ |
cl->motionConstraint->vector() = mc.vector(); |
| 289 |
|
|
|
| 290 |
|
|
const Matrix &T = |
| 291 |
|
✗ |
cl->contact.getForceGeneratorMatrix(); // e.g., 6x12 for a 6d contact |
| 292 |
|
✗ |
m_Jc.middleRows(cl->index, m).noalias() = T.transpose() * mc.matrix(); |
| 293 |
|
|
|
| 294 |
|
|
const ConstraintInequality &fc = |
| 295 |
|
✗ |
cl->contact.computeForceTask(time, q, v, m_data); |
| 296 |
|
✗ |
cl->forceConstraint->matrix().middleCols(m_v + cl->index, m) = fc.matrix(); |
| 297 |
|
✗ |
cl->forceConstraint->lowerBound() = fc.lowerBound(); |
| 298 |
|
✗ |
cl->forceConstraint->upperBound() = fc.upperBound(); |
| 299 |
|
|
|
| 300 |
|
|
const ConstraintEquality &fr = |
| 301 |
|
✗ |
cl->contact.computeForceRegularizationTask(time, q, v, m_data); |
| 302 |
|
✗ |
cl->forceRegTask->matrix().middleCols(m_v + cl->index, m) = fr.matrix(); |
| 303 |
|
✗ |
cl->forceRegTask->vector() = fr.vector(); |
| 304 |
|
|
} |
| 305 |
|
|
|
| 306 |
|
|
// Add all measured external forces to dynamic model |
| 307 |
|
✗ |
h_fext.setZero(m_v); |
| 308 |
|
✗ |
for (auto it : m_measuredForces) { |
| 309 |
|
✗ |
h_fext += it->measuredForce.computeJointTorques(m_data); |
| 310 |
|
|
} |
| 311 |
|
|
|
| 312 |
|
✗ |
const Matrix &M_a = m_robot.mass(m_data).bottomRows(m_v - m_u); |
| 313 |
|
|
const Vector &h_a = |
| 314 |
|
✗ |
m_robot.nonLinearEffects(m_data).tail(m_v - m_u) - h_fext.tail(m_v - m_u); |
| 315 |
|
✗ |
const Matrix &J_a = m_Jc.rightCols(m_v - m_u); |
| 316 |
|
✗ |
const Matrix &M_u = m_robot.mass(m_data).topRows(m_u); |
| 317 |
|
|
const Vector &h_u = |
| 318 |
|
✗ |
m_robot.nonLinearEffects(m_data).head(m_u) - h_fext.head(m_u); |
| 319 |
|
✗ |
const Matrix &J_u = m_Jc.leftCols(m_u); |
| 320 |
|
|
|
| 321 |
|
✗ |
m_baseDynamics->matrix().leftCols(m_v) = M_u; |
| 322 |
|
✗ |
m_baseDynamics->matrix().rightCols(m_k) = -J_u.transpose(); |
| 323 |
|
✗ |
m_baseDynamics->vector() = -h_u; |
| 324 |
|
|
|
| 325 |
|
|
// std::vector<TaskLevel*>::iterator it; |
| 326 |
|
|
// for(it=m_taskMotions.begin(); it!=m_taskMotions.end(); it++) |
| 327 |
|
✗ |
for (auto &it : m_taskMotions) { |
| 328 |
|
✗ |
const ConstraintBase &c = it->task.compute(time, q, v, m_data); |
| 329 |
|
✗ |
if (c.isEquality()) { |
| 330 |
|
✗ |
it->constraint->matrix().leftCols(m_v) = c.matrix(); |
| 331 |
|
✗ |
it->constraint->vector() = c.vector(); |
| 332 |
|
✗ |
} else if (c.isInequality()) { |
| 333 |
|
✗ |
it->constraint->matrix().leftCols(m_v) = c.matrix(); |
| 334 |
|
✗ |
it->constraint->lowerBound() = c.lowerBound(); |
| 335 |
|
✗ |
it->constraint->upperBound() = c.upperBound(); |
| 336 |
|
|
} else { |
| 337 |
|
✗ |
it->constraint->matrix().leftCols(m_v) = Matrix::Identity(m_v, m_v); |
| 338 |
|
✗ |
it->constraint->lowerBound() = c.lowerBound(); |
| 339 |
|
✗ |
it->constraint->upperBound() = c.upperBound(); |
| 340 |
|
|
} |
| 341 |
|
|
} |
| 342 |
|
|
|
| 343 |
|
✗ |
for (auto &it : m_taskContactForces) { |
| 344 |
|
|
// cout<<"Task "<<it->task.name()<<endl; |
| 345 |
|
|
// by default the task is associated to all contact forces |
| 346 |
|
✗ |
int i0 = m_v; |
| 347 |
|
✗ |
int c_size = m_k; |
| 348 |
|
|
|
| 349 |
|
|
// if the task is associated to a specific contact |
| 350 |
|
|
// cout<<"Associated contact name: |
| 351 |
|
|
// "<<it->task.getAssociatedContactName()<<endl; |
| 352 |
|
✗ |
if (it->task.getAssociatedContactName() != "") { |
| 353 |
|
|
// look for the associated contact |
| 354 |
|
✗ |
for (auto cl : m_contacts) { |
| 355 |
|
✗ |
if (it->task.getAssociatedContactName() == cl->contact.name()) { |
| 356 |
|
✗ |
i0 += cl->index; |
| 357 |
|
✗ |
c_size = cl->contact.n_force(); |
| 358 |
|
✗ |
break; |
| 359 |
|
|
} |
| 360 |
|
|
} |
| 361 |
|
|
} |
| 362 |
|
|
|
| 363 |
|
✗ |
const ConstraintBase &c = it->task.compute(time, q, v, m_data, &m_contacts); |
| 364 |
|
|
// cout<<"matrix"<<endl<<c.matrix()<<endl; |
| 365 |
|
|
// cout<<"vector"<<endl<<c.vector().transpose()<<endl; |
| 366 |
|
|
// cout<<"i0 "<<i0<<" c_size "<<c_size<<endl; |
| 367 |
|
|
// cout<<"constraint matrix size: "<<it->constraint->matrix().rows()<<" x |
| 368 |
|
|
// "<<it->constraint->matrix().cols()<<endl; |
| 369 |
|
|
|
| 370 |
|
✗ |
if (c.isEquality()) { |
| 371 |
|
✗ |
it->constraint->matrix().middleCols(i0, c_size) = c.matrix(); |
| 372 |
|
✗ |
it->constraint->vector() = c.vector(); |
| 373 |
|
✗ |
} else if (c.isInequality()) { |
| 374 |
|
✗ |
it->constraint->matrix().middleCols(i0, c_size) = c.matrix(); |
| 375 |
|
✗ |
it->constraint->lowerBound() = c.lowerBound(); |
| 376 |
|
✗ |
it->constraint->upperBound() = c.upperBound(); |
| 377 |
|
|
} else { |
| 378 |
|
✗ |
it->constraint->matrix().middleCols(i0, c_size) = |
| 379 |
|
✗ |
Matrix::Identity(c_size, c_size); |
| 380 |
|
✗ |
it->constraint->lowerBound() = c.lowerBound(); |
| 381 |
|
✗ |
it->constraint->upperBound() = c.upperBound(); |
| 382 |
|
|
} |
| 383 |
|
|
} |
| 384 |
|
|
|
| 385 |
|
✗ |
for (auto &it : m_taskActuations) { |
| 386 |
|
✗ |
const ConstraintBase &c = it->task.compute(time, q, v, m_data); |
| 387 |
|
✗ |
if (c.isEquality()) { |
| 388 |
|
✗ |
it->constraint->matrix().leftCols(m_v).noalias() = c.matrix() * M_a; |
| 389 |
|
✗ |
it->constraint->matrix().rightCols(m_k).noalias() = |
| 390 |
|
✗ |
-c.matrix() * J_a.transpose(); |
| 391 |
|
✗ |
it->constraint->vector() = c.vector(); |
| 392 |
|
✗ |
it->constraint->vector().noalias() -= c.matrix() * h_a; |
| 393 |
|
✗ |
} else if (c.isInequality()) { |
| 394 |
|
✗ |
it->constraint->matrix().leftCols(m_v).noalias() = c.matrix() * M_a; |
| 395 |
|
✗ |
it->constraint->matrix().rightCols(m_k).noalias() = |
| 396 |
|
✗ |
-c.matrix() * J_a.transpose(); |
| 397 |
|
✗ |
it->constraint->lowerBound() = c.lowerBound(); |
| 398 |
|
✗ |
it->constraint->lowerBound().noalias() -= c.matrix() * h_a; |
| 399 |
|
✗ |
it->constraint->upperBound() = c.upperBound(); |
| 400 |
|
✗ |
it->constraint->upperBound().noalias() -= c.matrix() * h_a; |
| 401 |
|
|
} else { |
| 402 |
|
|
// NB: An actuator bound becomes an inequality |
| 403 |
|
✗ |
it->constraint->matrix().leftCols(m_v) = M_a; |
| 404 |
|
✗ |
it->constraint->matrix().rightCols(m_k) = -J_a.transpose(); |
| 405 |
|
✗ |
it->constraint->lowerBound() = c.lowerBound() - h_a; |
| 406 |
|
✗ |
it->constraint->upperBound() = c.upperBound() - h_a; |
| 407 |
|
|
} |
| 408 |
|
|
} |
| 409 |
|
|
|
| 410 |
|
✗ |
m_solutionDecoded = false; |
| 411 |
|
|
|
| 412 |
|
✗ |
return m_hqpData; |
| 413 |
|
|
} |
| 414 |
|
|
|
| 415 |
|
✗ |
bool InverseDynamicsFormulationAccForce::decodeSolution(const HQPOutput &sol) { |
| 416 |
|
✗ |
if (m_solutionDecoded) return true; |
| 417 |
|
|
|
| 418 |
|
✗ |
const Matrix &M_a = m_robot.mass(m_data).bottomRows(m_v - m_u); |
| 419 |
|
|
const Vector &h_a = |
| 420 |
|
✗ |
m_robot.nonLinearEffects(m_data).tail(m_v - m_u) - h_fext.tail(m_v - m_u); |
| 421 |
|
✗ |
const Matrix &J_a = m_Jc.rightCols(m_v - m_u); |
| 422 |
|
✗ |
m_dv = sol.x.head(m_v); |
| 423 |
|
✗ |
m_f = sol.x.tail(m_k); |
| 424 |
|
✗ |
m_tau = h_a; |
| 425 |
|
✗ |
m_tau.noalias() += M_a * m_dv; |
| 426 |
|
✗ |
m_tau.noalias() -= J_a.transpose() * m_f; |
| 427 |
|
✗ |
m_solutionDecoded = true; |
| 428 |
|
✗ |
return true; |
| 429 |
|
|
} |
| 430 |
|
|
|
| 431 |
|
✗ |
const Vector &InverseDynamicsFormulationAccForce::getActuatorForces( |
| 432 |
|
|
const HQPOutput &sol) { |
| 433 |
|
✗ |
decodeSolution(sol); |
| 434 |
|
✗ |
return m_tau; |
| 435 |
|
|
} |
| 436 |
|
|
|
| 437 |
|
✗ |
const Vector &InverseDynamicsFormulationAccForce::getAccelerations( |
| 438 |
|
|
const HQPOutput &sol) { |
| 439 |
|
✗ |
decodeSolution(sol); |
| 440 |
|
✗ |
return m_dv; |
| 441 |
|
|
} |
| 442 |
|
|
|
| 443 |
|
✗ |
const Vector &InverseDynamicsFormulationAccForce::getContactForces( |
| 444 |
|
|
const HQPOutput &sol) { |
| 445 |
|
✗ |
decodeSolution(sol); |
| 446 |
|
✗ |
return m_f; |
| 447 |
|
|
} |
| 448 |
|
|
|
| 449 |
|
✗ |
Vector InverseDynamicsFormulationAccForce::getContactForces( |
| 450 |
|
|
const std::string &name, const HQPOutput &sol) { |
| 451 |
|
✗ |
decodeSolution(sol); |
| 452 |
|
|
// for(std::vector<ContactLevel*>::iterator it=m_contacts.begin(); |
| 453 |
|
|
// it!=m_contacts.end(); it++) |
| 454 |
|
✗ |
for (auto &it : m_contacts) { |
| 455 |
|
✗ |
if (it->contact.name() == name) { |
| 456 |
|
✗ |
const int k = it->contact.n_force(); |
| 457 |
|
✗ |
return m_f.segment(it->index, k); |
| 458 |
|
|
} |
| 459 |
|
|
} |
| 460 |
|
✗ |
return Vector::Zero(0); |
| 461 |
|
|
} |
| 462 |
|
|
|
| 463 |
|
✗ |
bool InverseDynamicsFormulationAccForce::getContactForces( |
| 464 |
|
|
const std::string &name, const HQPOutput &sol, RefVector f) { |
| 465 |
|
✗ |
decodeSolution(sol); |
| 466 |
|
✗ |
for (auto &it : m_contacts) { |
| 467 |
|
✗ |
if (it->contact.name() == name) { |
| 468 |
|
✗ |
const int k = it->contact.n_force(); |
| 469 |
|
✗ |
assert(f.size() == k); |
| 470 |
|
✗ |
f = m_f.segment(it->index, k); |
| 471 |
|
✗ |
return true; |
| 472 |
|
|
} |
| 473 |
|
|
} |
| 474 |
|
✗ |
return false; |
| 475 |
|
|
} |
| 476 |
|
|
|
| 477 |
|
✗ |
bool InverseDynamicsFormulationAccForce::removeTask(const std::string &taskName, |
| 478 |
|
|
double) { |
| 479 |
|
|
#ifndef NDEBUG |
| 480 |
|
✗ |
bool taskFound = removeFromHqpData(taskName); |
| 481 |
|
✗ |
assert(taskFound); |
| 482 |
|
|
#else |
| 483 |
|
|
removeFromHqpData(taskName); |
| 484 |
|
|
#endif |
| 485 |
|
|
|
| 486 |
|
✗ |
for (auto it = m_taskMotions.begin(); it != m_taskMotions.end(); it++) { |
| 487 |
|
✗ |
if ((*it)->task.name() == taskName) { |
| 488 |
|
✗ |
if ((*it)->priority == 0) { |
| 489 |
|
✗ |
if ((*it)->constraint->isEquality()) |
| 490 |
|
✗ |
m_eq -= (*it)->constraint->rows(); |
| 491 |
|
✗ |
else if ((*it)->constraint->isInequality()) |
| 492 |
|
✗ |
m_in -= (*it)->constraint->rows(); |
| 493 |
|
|
} |
| 494 |
|
✗ |
m_taskMotions.erase(it); |
| 495 |
|
✗ |
return true; |
| 496 |
|
|
} |
| 497 |
|
|
} |
| 498 |
|
✗ |
for (auto it = m_taskContactForces.begin(); it != m_taskContactForces.end(); |
| 499 |
|
✗ |
it++) { |
| 500 |
|
✗ |
if ((*it)->task.name() == taskName) { |
| 501 |
|
✗ |
m_taskContactForces.erase(it); |
| 502 |
|
✗ |
return true; |
| 503 |
|
|
} |
| 504 |
|
|
} |
| 505 |
|
✗ |
for (auto it = m_taskActuations.begin(); it != m_taskActuations.end(); it++) { |
| 506 |
|
✗ |
if ((*it)->task.name() == taskName) { |
| 507 |
|
✗ |
if ((*it)->priority == 0) { |
| 508 |
|
✗ |
if ((*it)->constraint->isEquality()) |
| 509 |
|
✗ |
m_eq -= (*it)->constraint->rows(); |
| 510 |
|
|
else |
| 511 |
|
✗ |
m_in -= (*it)->constraint->rows(); |
| 512 |
|
|
} |
| 513 |
|
✗ |
m_taskActuations.erase(it); |
| 514 |
|
✗ |
return true; |
| 515 |
|
|
} |
| 516 |
|
|
} |
| 517 |
|
✗ |
return false; |
| 518 |
|
|
} |
| 519 |
|
|
|
| 520 |
|
✗ |
bool InverseDynamicsFormulationAccForce::removeRigidContact( |
| 521 |
|
|
const std::string &contactName, double transition_duration) { |
| 522 |
|
✗ |
if (transition_duration > 0.0) { |
| 523 |
|
✗ |
for (auto &it : m_contacts) { |
| 524 |
|
✗ |
if (it->contact.name() == contactName) { |
| 525 |
|
✗ |
auto transitionInfo = std::make_shared<ContactTransitionInfo>(); |
| 526 |
|
✗ |
transitionInfo->contactLevel = it; |
| 527 |
|
✗ |
transitionInfo->time_start = m_t; |
| 528 |
|
✗ |
transitionInfo->time_end = m_t + transition_duration; |
| 529 |
|
✗ |
const int k = it->contact.n_force(); |
| 530 |
|
✗ |
if (m_f.size() >= it->index + k) { |
| 531 |
|
✗ |
const Vector f = m_f.segment(it->index, k); |
| 532 |
|
✗ |
transitionInfo->fMax_start = it->contact.getNormalForce(f); |
| 533 |
|
✗ |
} else { |
| 534 |
|
✗ |
transitionInfo->fMax_start = it->contact.getMaxNormalForce(); |
| 535 |
|
|
} |
| 536 |
|
✗ |
transitionInfo->fMax_end = it->contact.getMinNormalForce() + 1e-3; |
| 537 |
|
✗ |
m_contactTransitions.push_back(transitionInfo); |
| 538 |
|
✗ |
return true; |
| 539 |
|
|
} |
| 540 |
|
|
} |
| 541 |
|
✗ |
return false; |
| 542 |
|
|
} |
| 543 |
|
|
|
| 544 |
|
✗ |
bool first_constraint_found = removeFromHqpData(contactName + "_motion_task"); |
| 545 |
|
✗ |
assert(first_constraint_found); |
| 546 |
|
|
|
| 547 |
|
|
bool second_constraint_found = |
| 548 |
|
✗ |
removeFromHqpData(contactName + "_force_constraint"); |
| 549 |
|
✗ |
assert(second_constraint_found); |
| 550 |
|
|
|
| 551 |
|
|
bool third_constraint_found = |
| 552 |
|
✗ |
removeFromHqpData(contactName + "_force_reg_task"); |
| 553 |
|
✗ |
assert(third_constraint_found); |
| 554 |
|
|
|
| 555 |
|
✗ |
bool contact_found = false; |
| 556 |
|
✗ |
for (auto it = m_contacts.begin(); it != m_contacts.end(); it++) { |
| 557 |
|
✗ |
if ((*it)->contact.name() == contactName) { |
| 558 |
|
✗ |
m_k -= (*it)->contact.n_force(); |
| 559 |
|
✗ |
m_eq -= (*it)->motionConstraint->rows(); |
| 560 |
|
✗ |
m_in -= (*it)->forceConstraint->rows(); |
| 561 |
|
✗ |
m_contacts.erase(it); |
| 562 |
|
✗ |
resizeHqpData(); |
| 563 |
|
✗ |
contact_found = true; |
| 564 |
|
✗ |
break; |
| 565 |
|
|
} |
| 566 |
|
|
} |
| 567 |
|
|
|
| 568 |
|
✗ |
int k = 0; |
| 569 |
|
✗ |
for (auto &it : m_contacts) { |
| 570 |
|
✗ |
it->index = k; |
| 571 |
|
✗ |
k += it->contact.n_force(); |
| 572 |
|
|
} |
| 573 |
|
✗ |
return contact_found && first_constraint_found && second_constraint_found && |
| 574 |
|
✗ |
third_constraint_found; |
| 575 |
|
|
} |
| 576 |
|
|
|
| 577 |
|
✗ |
bool InverseDynamicsFormulationAccForce::removeMeasuredForce( |
| 578 |
|
|
const std::string &measuredForceName) { |
| 579 |
|
✗ |
for (auto it = m_measuredForces.begin(); it != m_measuredForces.end(); it++) { |
| 580 |
|
✗ |
if ((*it)->measuredForce.name() == measuredForceName) { |
| 581 |
|
✗ |
m_measuredForces.erase(it); |
| 582 |
|
✗ |
return true; |
| 583 |
|
|
} |
| 584 |
|
|
} |
| 585 |
|
✗ |
return false; |
| 586 |
|
|
} |
| 587 |
|
|
|
| 588 |
|
✗ |
bool InverseDynamicsFormulationAccForce::removeFromHqpData( |
| 589 |
|
|
const std::string &name) { |
| 590 |
|
✗ |
bool found = false; |
| 591 |
|
✗ |
for (HQPData::iterator it = m_hqpData.begin(); |
| 592 |
|
✗ |
!found && it != m_hqpData.end(); it++) { |
| 593 |
|
✗ |
for (ConstraintLevel::iterator itt = it->begin(); |
| 594 |
|
✗ |
!found && itt != it->end(); itt++) { |
| 595 |
|
✗ |
if (itt->second->name() == name) { |
| 596 |
|
✗ |
it->erase(itt); |
| 597 |
|
✗ |
return true; |
| 598 |
|
|
} |
| 599 |
|
|
} |
| 600 |
|
|
} |
| 601 |
|
✗ |
return false; |
| 602 |
|
|
} |
| 603 |
|
|
|