contact-two-frames.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2023 MIPT
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 #ifndef __tsid_python_contact_two_frames_hpp__
19 #define __tsid_python_contact_two_frames_hpp__
20 
22 
23 #include "tsid/contacts/contact-two-frames.hpp"
28 
29 namespace tsid {
30 namespace python {
31 namespace bp = boost::python;
32 
33 template <typename ContactTwoFrames>
35  : public boost::python::def_visitor<
36  ContactTwoFramesPythonVisitor<ContactTwoFrames> > {
37  template <class PyClass>
38 
39  void visit(PyClass& cl) const {
40  cl
41  .def(bp::init<std::string, robots::RobotWrapper&, std::string,
42  std::string, double, double>(
43  (bp::arg("name"), bp::arg("robot"), bp::arg("framename1"),
44  bp::arg("framename2"), bp::arg("minForce"), bp::arg("maxForce")),
45  "Default Constructor"))
46  .add_property("n_motion", &ContactTwoFrames::n_motion,
47  "return number of motion")
48  .add_property("n_force", &ContactTwoFrames::n_force,
49  "return number of force")
50  .add_property("name", &ContactTwoFramesPythonVisitor::name,
51  "return name")
52  .def("computeMotionTask",
54  bp::args("t", "q", "v", "data"))
55  .def("computeForceTask",
57  bp::args("t", "q", "v", "data"))
58  .def("computeForceRegularizationTask",
60  bp::args("t", "q", "v", "data"))
61 
62  .add_property(
63  "getForceGeneratorMatrix",
64  bp::make_function(
66  bp::return_value_policy<bp::copy_const_reference>()))
67 
68  .def("getNormalForce", &ContactTwoFramesPythonVisitor::getNormalForce,
69  bp::arg("vec"))
70  .add_property("getMinNormalForce", &ContactTwoFrames::getMinNormalForce)
71  .add_property("getMaxNormalForce", &ContactTwoFrames::getMaxNormalForce)
72 
73  .add_property("Kp",
74  bp::make_function(
76  bp::return_value_policy<bp::copy_const_reference>()))
77  .add_property("Kd",
78  bp::make_function(
80  bp::return_value_policy<bp::copy_const_reference>()))
81  .def("setKp", &ContactTwoFramesPythonVisitor::setKp, bp::arg("Kp"))
82  .def("setKd", &ContactTwoFramesPythonVisitor::setKd, bp::arg("Kd"))
83 
84  .def("useLocalFrame", &ContactTwoFramesPythonVisitor::useLocalFrame,
85  bp::arg("local_frame"))
86 
87  .def("setContactNormal",
89  .def("setFrictionCoefficient",
91  bp::args("friction_coeff"))
92  .def("setMinNormalForce",
94  bp::args("min_force"))
95  .def("setMaxNormalForce",
97  bp::args("max_force"))
98  .def("setReference", &ContactTwoFramesPythonVisitor::setReference,
99  bp::args("SE3"))
100  .def("setForceReference",
102  bp::args("f_vec"))
103  .def("setRegularizationTaskWeightVector",
105  bp::args("w_vec"));
106  }
107  static std::string name(ContactTwoFrames& self) {
108  std::string name = self.name();
109  return name;
110  }
111 
112  static math::ConstraintEquality computeMotionTask(ContactTwoFrames& self,
113  const double t,
114  const Eigen::VectorXd& q,
115  const Eigen::VectorXd& v,
117  self.computeMotionTask(t, q, v, data);
118  math::ConstraintEquality cons(self.getMotionConstraint().name(),
119  self.getMotionConstraint().matrix(),
120  self.getMotionConstraint().vector());
121  return cons;
122  }
124  ContactTwoFrames& self, const double t, const Eigen::VectorXd& q,
125  const Eigen::VectorXd& v, const pinocchio::Data& data) {
126  self.computeForceTask(t, q, v, data);
127  math::ConstraintInequality cons(self.getForceConstraint().name(),
128  self.getForceConstraint().matrix(),
129  self.getForceConstraint().lowerBound(),
130  self.getForceConstraint().upperBound());
131  return cons;
132  }
134  ContactTwoFrames& self, const double t, const Eigen::VectorXd& q,
135  const Eigen::VectorXd& v, const pinocchio::Data& data) {
136  self.computeForceRegularizationTask(t, q, v, data);
137  math::ConstraintEquality cons(self.getForceRegularizationTask().name(),
138  self.getForceRegularizationTask().matrix(),
139  self.getForceRegularizationTask().vector());
140  return cons;
141  }
142 
143  static void useLocalFrame(ContactTwoFrames& self, const bool local_frame) {
144  self.useLocalFrame(local_frame);
145  }
146  static const Eigen::MatrixXd& getForceGeneratorMatrix(
147  ContactTwoFrames& self) {
148  return self.getForceGeneratorMatrix();
149  }
150  static const Eigen::VectorXd& Kp(ContactTwoFrames& self) { return self.Kp(); }
151  static const Eigen::VectorXd& Kd(ContactTwoFrames& self) { return self.Kd(); }
152  static void setKp(ContactTwoFrames& self, const ::Eigen::VectorXd Kp) {
153  return self.Kp(Kp);
154  }
155  static void setKd(ContactTwoFrames& self, const ::Eigen::VectorXd Kd) {
156  return self.Kd(Kd);
157  }
158  static bool setContactTwoFramess(ContactTwoFrames& self,
159  const ::Eigen::MatrixXd ContactTwoFramess) {
160  return self.setContactTwoFramess(ContactTwoFramess);
161  }
162  static bool setContactNormal(ContactTwoFrames& self,
163  const ::Eigen::VectorXd contactNormal) {
164  return self.setContactNormal(contactNormal);
165  }
166  static bool setFrictionCoefficient(ContactTwoFrames& self,
167  const double frictionCoefficient) {
168  return self.setFrictionCoefficient(frictionCoefficient);
169  }
170  static bool setMinNormalForce(ContactTwoFrames& self,
171  const double minNormalForce) {
172  return self.setMinNormalForce(minNormalForce);
173  }
174  static bool setMaxNormalForce(ContactTwoFrames& self,
175  const double maxNormalForce) {
176  return self.setMaxNormalForce(maxNormalForce);
177  }
178  static void setReference(ContactTwoFrames& self, const pinocchio::SE3& ref) {
179  self.setReference(ref);
180  }
181  static void setForceReference(ContactTwoFrames& self,
182  const ::Eigen::VectorXd f_ref) {
183  self.setForceReference(f_ref);
184  }
185  static void setRegularizationTaskWeightVector(ContactTwoFrames& self,
186  const ::Eigen::VectorXd w) {
187  self.setRegularizationTaskWeightVector(w);
188  }
189  static double getNormalForce(ContactTwoFrames& self, Eigen::VectorXd f) {
190  return self.getNormalForce(f);
191  }
192 
193  static void expose(const std::string& class_name) {
194  std::string doc = "ContactTwoFrames info.";
195  bp::class_<ContactTwoFrames>(class_name.c_str(), doc.c_str(), bp::no_init)
197  }
198 };
199 } // namespace python
200 } // namespace tsid
201 
202 #endif // ifndef __tsid_python_contact_two_frames_hpp__
demo_quadruped.v
v
Definition: demo_quadruped.py:80
init
void init(bool compute_local_aabb=true)
boost::python
class_name
str class_name(str s)
pinocchio::DataTpl
tsid::math::ConstraintEquality
Definition: math/constraint-equality.hpp:26
tsid::python::ContactTwoFramesPythonVisitor::useLocalFrame
static void useLocalFrame(ContactTwoFrames &self, const bool local_frame)
Definition: contact-two-frames.hpp:143
tsid::python::ContactTwoFramesPythonVisitor::setForceReference
static void setForceReference(ContactTwoFrames &self, const ::Eigen::VectorXd f_ref)
Definition: contact-two-frames.hpp:181
tsid::python::ContactTwoFramesPythonVisitor::computeForceTask
static math::ConstraintInequality computeForceTask(ContactTwoFrames &self, const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const pinocchio::Data &data)
Definition: contact-two-frames.hpp:123
pinocchio::SE3
context::SE3 SE3
ref
list ref
setup.data
data
Definition: setup.in.py:48
tsid::python::ContactTwoFramesPythonVisitor::setKp
static void setKp(ContactTwoFrames &self, const ::Eigen::VectorXd Kp)
Definition: contact-two-frames.hpp:152
tsid::python::ContactTwoFramesPythonVisitor::setContactNormal
static bool setContactNormal(ContactTwoFrames &self, const ::Eigen::VectorXd contactNormal)
Definition: contact-two-frames.hpp:162
tsid::python::ContactTwoFramesPythonVisitor::computeForceRegularizationTask
static math::ConstraintEquality computeForceRegularizationTask(ContactTwoFrames &self, const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const pinocchio::Data &data)
Definition: contact-two-frames.hpp:133
tsid::python::ContactTwoFramesPythonVisitor::setMaxNormalForce
static bool setMaxNormalForce(ContactTwoFrames &self, const double maxNormalForce)
Definition: contact-two-frames.hpp:174
tsid::python::ContactTwoFramesPythonVisitor
Definition: contact-two-frames.hpp:34
constraint-equality.hpp
tsid::python::ContactTwoFramesPythonVisitor::getNormalForce
static double getNormalForce(ContactTwoFrames &self, Eigen::VectorXd f)
Definition: contact-two-frames.hpp:189
f
f
tsid::python::ContactTwoFramesPythonVisitor::name
static std::string name(ContactTwoFrames &self)
Definition: contact-two-frames.hpp:107
tsid::python::ContactTwoFramesPythonVisitor::setFrictionCoefficient
static bool setFrictionCoefficient(ContactTwoFrames &self, const double frictionCoefficient)
Definition: contact-two-frames.hpp:166
tsid::python::ContactTwoFramesPythonVisitor::setMinNormalForce
static bool setMinNormalForce(ContactTwoFrames &self, const double minNormalForce)
Definition: contact-two-frames.hpp:170
tsid::python::ContactTwoFramesPythonVisitor::Kp
static const Eigen::VectorXd & Kp(ContactTwoFrames &self)
Definition: contact-two-frames.hpp:150
demo_quadruped.q
q
Definition: demo_quadruped.py:74
tsid::python::ContactTwoFramesPythonVisitor::expose
static void expose(const std::string &class_name)
Definition: contact-two-frames.hpp:193
tsid::python::ContactTwoFramesPythonVisitor::getForceGeneratorMatrix
static const Eigen::MatrixXd & getForceGeneratorMatrix(ContactTwoFrames &self)
Definition: contact-two-frames.hpp:146
tsid::python::ContactTwoFramesPythonVisitor::setKd
static void setKd(ContactTwoFrames &self, const ::Eigen::VectorXd Kd)
Definition: contact-two-frames.hpp:155
robot-wrapper.hpp
python
tsid::python::ContactTwoFramesPythonVisitor::computeMotionTask
static math::ConstraintEquality computeMotionTask(ContactTwoFrames &self, const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, pinocchio::Data &data)
Definition: contact-two-frames.hpp:112
constraint-base.hpp
demo_quadruped.vector
vector
Definition: demo_quadruped.py:49
tsid::math::ConstraintInequality
Definition: math/constraint-inequality.hpp:26
tsid::python::ContactTwoFramesPythonVisitor::visit
void visit(PyClass &cl) const
Definition: contact-two-frames.hpp:39
w
w
constraint-inequality.hpp
tsid::python::ContactTwoFramesPythonVisitor::setReference
static void setReference(ContactTwoFrames &self, const pinocchio::SE3 &ref)
Definition: contact-two-frames.hpp:178
tsid
Definition: bindings/python/constraint/constraint-bound.cpp:21
tsid::python::ContactTwoFramesPythonVisitor::setContactTwoFramess
static bool setContactTwoFramess(ContactTwoFrames &self, const ::Eigen::MatrixXd ContactTwoFramess)
Definition: contact-two-frames.hpp:158
tsid::robots::RobotWrapper
Wrapper for a robot based on pinocchio.
Definition: robots/robot-wrapper.hpp:37
cl
cl
tsid::python::ContactTwoFramesPythonVisitor::Kd
static const Eigen::VectorXd & Kd(ContactTwoFrames &self)
Definition: contact-two-frames.hpp:151
fwd.hpp
t
Transform3f t
demo_quadruped.contactNormal
contactNormal
Definition: demo_quadruped.py:29
tsid::python::ContactTwoFramesPythonVisitor::setRegularizationTaskWeightVector
static void setRegularizationTaskWeightVector(ContactTwoFrames &self, const ::Eigen::VectorXd w)
Definition: contact-two-frames.hpp:185


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