task-capture-point-inequality.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2020 CNRS, NYU, MPI Tübingen, PAL Robotics
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 //
18 #include "tsid/math/utils.hpp"
20 
27 namespace tsid {
28 namespace tasks {
29 using namespace math;
30 using namespace trajectories;
31 using namespace pinocchio;
32 
35  const double timeStep)
36  : TaskMotion(name, robot),
37  m_constraint(name, 2, robot.nv()),
38  m_nv(robot.nv()),
39  m_delta_t(timeStep) {
40  m_dim = 2;
41  m_p_com.setZero(3);
42  m_v_com.setZero(3);
43 
44  m_safety_margin.setZero(m_dim);
45 
46  m_support_limits_x.setZero(m_dim);
47  m_support_limits_y.setZero(m_dim);
48 
49  m_rp_max.setZero(m_dim);
50  m_rp_min.setZero(m_dim);
51 
52  b_lower.setZero(m_dim);
53  b_upper.setZero(m_dim);
54 
55  m_g = robot.model().gravity.linear().norm();
56  m_w = 0;
57  m_ka = 0;
58 }
59 
60 int TaskCapturePointInequality::dim() const { return m_dim; }
61 
63  return m_constraint.matrix() * dv - m_drift;
64 }
65 
68  return m_constraint;
69 }
70 
72  const double x_max) {
73  PINOCCHIO_CHECK_INPUT_ARGUMENT(x_min >= x_max,
74  "The minimum limit for x needs to be greater "
75  "or equal to the maximum limit");
76  m_support_limits_x(0) = x_min;
77  m_support_limits_x(1) = x_max;
78 }
79 
81  const double y_max) {
82  PINOCCHIO_CHECK_INPUT_ARGUMENT(y_min >= y_max,
83  "The minimum limit for y needs to be greater "
84  "or equal to the maximum limit");
85  m_support_limits_y(0) = y_min;
86  m_support_limits_y(1) = y_max;
87 }
88 
90  const double y_margin) {
91  m_safety_margin(0) = x_margin;
92  m_safety_margin(1) = y_margin;
93 }
94 
98  Data& data) {
100 
101  const Matrix3x& Jcom = m_robot.Jcom(data);
102 
103  m_w = sqrt(m_g / m_p_com(2));
104  m_ka = (2 * m_w) / ((m_w * m_delta_t + 2) * m_delta_t);
105 
106  m_rp_min(0) =
107  m_support_limits_x(0) + m_safety_margin(0); // x min support polygon
108  m_rp_min(1) =
109  m_support_limits_y(0) + m_safety_margin(1); // y min support polygon
110 
111  m_rp_max(0) =
112  m_support_limits_x(1) - m_safety_margin(0); // x max support polygon
113  m_rp_max(1) =
114  m_support_limits_y(1) - m_safety_margin(1); // y max support polygon
115 
116  for (int i = 0; i < m_dim; i++) {
117  b_lower(i) =
118  m_ka * (m_rp_min(i) - m_p_com(i) - m_v_com(i) * (m_delta_t + 1 / m_w));
119  b_upper(i) =
120  m_ka * (m_rp_max(i) - m_p_com(i) - m_v_com(i) * (m_delta_t + 1 / m_w));
121  }
122 
123  m_constraint.lowerBound() = b_lower - m_drift.head(m_dim);
124  m_constraint.upperBound() = b_upper - m_drift.head(m_dim);
125 
126  m_constraint.setMatrix(Jcom.block(0, 0, m_dim, m_nv));
127 
128  return m_constraint;
129 }
130 
131 } // namespace tasks
132 } // namespace tsid
const Matrix3x & Jcom(const Data &data) const
TaskCapturePointInequality(const std::string &name, RobotWrapper &robot, const double timeStep)
int i
void setSupportLimitsXAxis(const double x_min, const double x_max)
RobotWrapper & m_robot
Reference on the robot model.
Definition: task-base.hpp:64
const Model & model() const
Accessor to model.
data
Definition: setup.in.py:48
ConstLinearType linear() const
void setSafetyMargin(const double x_margin, const double y_margin)
virtual bool setMatrix(ConstRefMatrix A)
math::ConstRefVector ConstRefVector
Definition: task-base.hpp:39
int nv
Definition: ex_4_conf.py:25
void setSupportLimitsYAxis(const double y_min, const double y_max)
void com(const Data &data, RefVector com_pos, RefVector com_vel, RefVector com_acc) const
Eigen::Matrix< Scalar, 3, Eigen::Dynamic > Matrix3x
Definition: math/fwd.hpp:42
Wrapper for a robot based on pinocchio.
int dim() const
Return the dimension of the task. should be overloaded in the child class.
virtual const Matrix & matrix() const
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
const ConstraintBase & compute(const double t, ConstRefVector q, ConstRefVector v, Data &data)


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sun Jul 2 2023 02:21:51