src/tasks/task-cop-equality.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021 University of Trento
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 
19 
20 using namespace tsid::math;
21 using namespace std;
22 
23 namespace tsid {
24 namespace tasks {
25 
26 TaskCopEquality::TaskCopEquality(const std::string& name, RobotWrapper& robot)
28  m_contact_name(""),
29  m_constraint(name, 3, 3) {
30  m_normal << 0, 0, 1;
31  m_ref.setZero();
32 }
33 
35  const std::vector<std::shared_ptr<ContactLevel> >* contacts) {
37 }
38 
39 int TaskCopEquality::dim() const { return 3; }
40 
42  return m_contact_name;
43 }
44 
46  const double t, ConstRefVector q, ConstRefVector v, Data& data,
47  const std::vector<std::shared_ptr<ContactLevel> >* contacts) {
49  return compute(t, q, v, data);
50 }
53  // count size of force vector
54  int n = 0;
55  for (auto& cl : *m_contacts) {
56  n += cl->contact.n_force();
57  }
58 
59  // fill constraint matrix
60  SE3 oMi;
61  Vector3 p_local, p_world;
62  auto& M = m_constraint.matrix();
63  M.resize(3, n);
64  for (auto& cl : *m_contacts) {
65  unsigned int i = cl->index;
66  // get contact points in local frame and transform them to world frame
67  const Matrix3x& P = cl->contact.getContactPoints();
69  data,
70  static_cast<const TaskSE3Equality&>(cl->contact.getMotionTask())
71  .frame_id(),
72  oMi);
73  // cout<<"Contact "<<cl->contact.name()<<endl;
74  // cout<<"oMi\n"<<oMi<<endl;
75  for (int j = 0; j < P.cols(); ++j) {
76  p_local = P.col(j);
77  p_world = oMi.act(p_local);
78  // cout<<j<<" p_local "<<p_local.transpose()<<endl;
79  // cout<<j<<" p_world "<<p_world.transpose()<<endl;
80  M.middleCols(i + 3 * j, 3) = (p_world - m_ref) * (m_normal.transpose());
81  }
82  }
83  return m_constraint;
84 }
85 
87  return m_constraint;
88 }
89 
92  "The size of the reference needs to equal 3");
93  m_ref = ref;
94 }
95 
96 const Vector3& TaskCopEquality::getReference() const { return m_ref; }
97 
99 
101 
102 } // namespace tasks
103 } // namespace tsid
tsid::robots::RobotWrapper::framePosition
SE3 framePosition(const Data &data, const Model::FrameIndex index) const
Definition: src/robots/robot-wrapper.cpp:216
demo_quadruped.v
v
Definition: demo_quadruped.py:80
tsid::tasks::TaskCopEquality::m_contacts
const std::vector< std::shared_ptr< ContactLevel > > * m_contacts
Definition: tasks/task-cop-equality.hpp:68
tsid::tasks::TaskCopEquality::m_normal
Vector3 m_normal
Definition: tasks/task-cop-equality.hpp:70
tsid::tasks::TaskCopEquality::m_constraint
ConstraintEquality m_constraint
Definition: tasks/task-cop-equality.hpp:72
pinocchio::DataTpl
PINOCCHIO_CHECK_INPUT_ARGUMENT
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
task-cop-equality.hpp
tsid::tasks::TaskCopEquality::setContactNormal
void setContactNormal(const Vector3 &n)
Definition: src/tasks/task-cop-equality.cpp:98
tsid::math::ConstraintBase
Abstract class representing a linear equality/inequality constraint. Equality constraints are represe...
Definition: constraint-base.hpp:35
tsid::tasks::TaskContactForce
Definition: task-contact-force.hpp:28
i
int i
ref
list ref
setup.data
data
Definition: setup.in.py:48
tsid::tasks::TaskCopEquality::setContactList
void setContactList(const std::vector< std::shared_ptr< ContactLevel > > *contacts)
Definition: src/tasks/task-cop-equality.cpp:34
demo_quadruped.robot
robot
Definition: demo_quadruped.py:51
tsid::math::Matrix3x
Eigen::Matrix< Scalar, 3, Eigen::Dynamic > Matrix3x
Definition: math/fwd.hpp:42
tsid::math
Definition: constraint-base.hpp:26
tsid::tasks::TaskCopEquality::m_contact_name
std::string m_contact_name
Definition: tasks/task-cop-equality.hpp:69
demo_quadruped.q
q
Definition: demo_quadruped.py:74
tsid::tasks::TaskCopEquality::compute
const ConstraintBase & compute(double t, ConstRefVector q, ConstRefVector v, Data &data) override
Definition: src/tasks/task-cop-equality.cpp:51
tsid::math::ConstraintBase::matrix
virtual const Matrix & matrix() const
Definition: constraint-base.cpp:35
P
P
tsid::tasks::TaskCopEquality::getAssociatedContactName
const std::string & getAssociatedContactName() override
Definition: src/tasks/task-cop-equality.cpp:41
demo_quadruped.vector
vector
Definition: demo_quadruped.py:49
M
M
demo_quadruped.contacts
int contacts
Definition: demo_quadruped.py:98
tsid::tasks::TaskCopEquality::getReference
const Vector3 & getReference() const
Definition: src/tasks/task-cop-equality.cpp:96
setup.name
name
Definition: setup.in.py:179
tsid::tasks::TaskCopEquality::m_ref
Vector3 m_ref
Definition: tasks/task-cop-equality.hpp:71
tsid::tasks::TaskCopEquality::getConstraint
const ConstraintBase & getConstraint() const override
Definition: src/tasks/task-cop-equality.cpp:86
tsid::tasks::TaskSE3Equality::frame_id
Index frame_id() const
Definition: src/tasks/task-se3-equality.cpp:139
tsid::tasks::TaskCopEquality::setReference
void setReference(const Vector3 &ref)
Definition: src/tasks/task-cop-equality.cpp:90
tsid
Definition: bindings/python/constraint/constraint-bound.cpp:21
std
tsid::tasks::TaskCopEquality::getContactNormal
const Vector3 & getContactNormal() const
Definition: src/tasks/task-cop-equality.cpp:100
tsid::robots::RobotWrapper
Wrapper for a robot based on pinocchio.
Definition: robots/robot-wrapper.hpp:37
cl
cl
tsid::tasks::TaskCopEquality::Vector3
math::Vector3 Vector3
Definition: tasks/task-cop-equality.hpp:37
tsid::tasks::TaskCopEquality::SE3
pinocchio::SE3 SE3
Definition: tasks/task-cop-equality.hpp:39
t
Transform3f t
tsid::tasks::TaskBase::m_robot
RobotWrapper & m_robot
Reference on the robot model.
Definition: task-base.hpp:64
tsid::tasks::TaskSE3Equality
Definition: tasks/task-se3-equality.hpp:31
tsid::tasks::TaskCopEquality::dim
int dim() const override
Return the dimension of the task. \info should be overloaded in the child class.
Definition: src/tasks/task-cop-equality.cpp:39
tsid::tasks::TaskBase::ConstRefVector
math::ConstRefVector ConstRefVector
Definition: task-base.hpp:39
n
Vec3f n


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Thu Apr 3 2025 02:47:16