src/tasks/task-se3-equality.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2017-2020 CNRS, NYU, MPI Tübingen, Inria
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/math/utils.hpp"
21 
22 namespace tsid {
23 namespace tasks {
24 using namespace std;
25 using namespace math;
26 using namespace trajectories;
27 using namespace pinocchio;
28 
30  const std::string& frameName)
31  : TaskMotion(name, robot),
32  m_frame_name(frameName),
33  m_constraint(name, 6, robot.nv()),
34  m_ref(12, 6) {
36  m_robot.model().existFrame(frameName),
37  "The frame with name '" + frameName + "' does not exist");
38  m_frame_id = m_robot.model().getFrameId(frameName);
39 
40  m_v_ref.setZero();
41  m_a_ref.setZero();
44  m_p_error_vec.setZero(6);
45  m_v_error_vec.setZero(6);
46  m_p.resize(12);
47  m_v.resize(6);
48  m_p_ref.resize(12);
49  m_v_ref_vec.resize(6);
50  m_Kp.setZero(6);
51  m_Kd.setZero(6);
52  m_a_des.setZero(6);
53  m_J.setZero(6, robot.nv());
54  m_J_rotated.setZero(6, robot.nv());
55 
56  m_mask.resize(6);
57  m_mask.fill(1.);
58  setMask(m_mask);
59 
60  m_local_frame = true;
61 }
62 
64  TaskMotion::setMask(mask);
65  int n = dim();
66  m_constraint.resize(n, (unsigned int)m_J.cols());
67  m_p_error_masked_vec.resize(n);
68  m_v_error_masked_vec.resize(n);
69  m_drift_masked.resize(n);
70  m_a_des_masked.resize(n);
71 }
72 
73 int TaskSE3Equality::dim() const { return (int)m_mask.sum(); }
74 
75 const Vector& TaskSE3Equality::Kp() const { return m_Kp; }
76 
77 const Vector& TaskSE3Equality::Kd() const { return m_Kd; }
78 
80  PINOCCHIO_CHECK_INPUT_ARGUMENT(Kp.size() == 6,
81  "The size of the Kp vector needs to equal 6");
82  m_Kp = Kp;
83 }
84 
86  PINOCCHIO_CHECK_INPUT_ARGUMENT(Kd.size() == 6,
87  "The size of the Kd vector needs to equal 6");
88  m_Kd = Kd;
89 }
90 
92  m_ref = ref;
96  ref.pos.size() == 12, "The size of the reference vector needs to be 12");
97  m_M_ref.translation(ref.pos.head<3>());
98  m_M_ref.rotation(MapMatrix3(&ref.pos(3), 3, 3));
100  m_v_ref = Motion(ref.getDerivative());
102 }
103 
105  TrajectorySample s(12, 6);
110  setReference(s);
111 }
112 
114 
116  return m_p_error_masked_vec;
117 }
118 
120  return m_v_error_masked_vec;
121 }
122 
123 const Vector& TaskSE3Equality::position() const { return m_p; }
124 
125 const Vector& TaskSE3Equality::velocity() const { return m_v; }
126 
127 const Vector& TaskSE3Equality::position_ref() const { return m_p_ref; }
128 
130 
132  return m_a_des_masked;
133 }
134 
136  return m_constraint.matrix() * dv + m_drift_masked;
137 }
138 
140 
142  return m_constraint;
143 }
144 
145 void TaskSE3Equality::useLocalFrame(bool local_frame) {
146  m_local_frame = local_frame;
147 }
148 
151  SE3 oMi;
152  Motion v_frame;
153  m_robot.framePosition(data, m_frame_id, oMi);
154  m_robot.frameVelocity(data, m_frame_id, v_frame);
156 
157  // @todo Since Jacobian computation is cheaper in world frame
158  // we could do all computations in world frame
160 
161  errorInSE3(oMi, m_M_ref, m_p_error); // pos err in local frame
163  SE3ToVector(oMi, m_p);
164 
165  // Transformation from local to world
166  m_wMl.rotation(oMi.rotation());
167 
168  if (m_local_frame) {
170  m_v_error = m_wMl.actInv(m_v_ref) - v_frame; // vel err in local frame
171 
172  // desired acc in local frame
173  m_a_des = m_Kp.cwiseProduct(m_p_error_vec) +
174  m_Kd.cwiseProduct(m_v_error.toVector()) +
175  m_wMl.actInv(m_a_ref).toVector();
176  } else {
177  m_p_error_vec =
178  m_wMl.toActionMatrix() * // pos err in local world-oriented frame
180 
181  // cout<<"m_p_error_vec="<<m_p_error_vec.head<3>().transpose()<<endl;
182  // cout<<"oMi-m_M_ref
183  // ="<<-(oMi.translation()-m_M_ref.translation()).transpose()<<endl;
184 
185  m_v_error =
186  m_v_ref - m_wMl.act(v_frame); // vel err in local world-oriented frame
187 
188  m_drift = m_wMl.act(m_drift);
189 
190  // desired acc in local world-oriented frame
191  m_a_des = m_Kp.cwiseProduct(m_p_error_vec) +
192  m_Kd.cwiseProduct(m_v_error.toVector()) + m_a_ref.toVector();
193 
194  // Use an explicit temporary `m_J_rotated` here to avoid allocations.
195  m_J_rotated.noalias() = m_wMl.toActionMatrix() * m_J;
196  m_J = m_J_rotated;
197  }
198 
201  m_v = v_frame.toVector();
202 
203  int idx = 0;
204  for (int i = 0; i < 6; i++) {
205  if (m_mask(i) != 1.) continue;
206 
207  m_constraint.matrix().row(idx) = m_J.row(i);
208  m_constraint.vector().row(idx) = (m_a_des - m_drift.toVector()).row(i);
209  m_a_des_masked(idx) = m_a_des(i);
210  m_drift_masked(idx) = m_drift.toVector()(i);
213 
214  idx += 1;
215  }
216 
217  return m_constraint;
218 }
219 } // namespace tasks
220 } // namespace tsid
s
Vec3f n
void SE3ToVector(const pinocchio::SE3 &M, RefVector vec)
int i
bool existFrame(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
#define TSID_DISABLE_WARNING_POP
Definition: macros.hpp:26
RobotWrapper & m_robot
Reference on the robot model.
Definition: task-base.hpp:64
#define TSID_DISABLE_WARNING_PUSH
Definition: macros.hpp:25
const TrajectorySample & getReference() const
const Model & model() const
Accessor to model.
#define TSID_DISABLE_WARNING_DEPRECATED
Definition: macros.hpp:27
Motion frameClassicAcceleration(const Data &data, const Model::FrameIndex index) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW TSID_DEPRECATED math::Vector pos
TaskSE3Equality(const std::string &name, RobotWrapper &robot, const std::string &frameName)
void useLocalFrame(bool local_frame)
Specifies if the jacobian and desired acceloration should be expressed in the local frame or the loca...
data
Definition: setup.in.py:48
SE3Tpl & setIdentity()
SE3 framePosition(const Data &data, const Model::FrameIndex index) const
Eigen::Map< const Eigen::Matrix< double, 3, 3 > > MapMatrix3
math::ConstRefVector ConstRefVector
Definition: task-base.hpp:39
virtual void setMask(math::ConstRefVector mask)
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
void errorInSE3(const pinocchio::SE3 &M, const pinocchio::SE3 &Mdes, pinocchio::Motion &error)
void setReference(TrajectorySample &ref)
int nv
Definition: ex_4_conf.py:25
const Eigen::Ref< const Vector > ConstRefVector
Definition: math/fwd.hpp:48
void frameJacobianLocal(Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const
Wrapper for a robot based on pinocchio.
ToVectorConstReturnType toVector() const
std::size_t Index
virtual const Matrix & matrix() const
const ConstraintBase & compute(const double t, ConstRefVector q, ConstRefVector v, Data &data)
Motion frameVelocity(const Data &data, const Model::FrameIndex index) const
MotionTpl< _Scalar, _Options > & setZero()
Vector getAcceleration(ConstRefVector dv) const
virtual void setMask(math::ConstRefVector mask)
Definition: task-motion.cpp:29
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
string frameName
Definition: test_Contact.py:29
int dim() const
Return the dimension of the task. should be overloaded in the child class.
void resize(const unsigned int r, const unsigned int c)
const ConstraintBase & getConstraint() const


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