task-am-equality.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018 CNRS
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_task_am_hpp__
19 #define __tsid_python_task_am_hpp__
20 
22 
28 namespace tsid {
29 namespace python {
30 namespace bp = boost::python;
31 
32 template <typename TaskAM>
34  : public boost::python::def_visitor<TaskAMEqualityPythonVisitor<TaskAM> > {
35  template <class PyClass>
36 
37  void visit(PyClass& cl) const {
38  cl.def(bp::init<std::string, robots::RobotWrapper&>(
39  (bp::arg("name"), bp::arg("robot")), "Default Constructor"))
40  .add_property("dim", &TaskAM::dim, "return dimension size")
41  .def("setReference", &TaskAMEqualityPythonVisitor::setReference,
42  bp::arg("ref"))
43  .add_property(
44  "getDesiredMomentumDerivative",
45  bp::make_function(
47  bp::return_value_policy<bp::copy_const_reference>()),
48  "Return dL_desired")
49  .def("getdMomentum", &TaskAMEqualityPythonVisitor::getdMomentum,
50  bp::arg("dv"))
51  .add_property("momentum_error",
52  bp::make_function(
54  bp::return_value_policy<bp::copy_const_reference>()))
55  .add_property("momentum",
56  bp::make_function(
58  bp::return_value_policy<bp::copy_const_reference>()))
59  .add_property("momentum_ref",
60  bp::make_function(
62  bp::return_value_policy<bp::copy_const_reference>()))
63  .add_property("dmomentum_ref",
64  bp::make_function(
66  bp::return_value_policy<bp::copy_const_reference>()))
67  .add_property("Kp",
68  bp::make_function(
70  bp::return_value_policy<bp::copy_const_reference>()))
71  .add_property("Kd",
72  bp::make_function(
74  bp::return_value_policy<bp::copy_const_reference>()))
75  .def("setKp", &TaskAMEqualityPythonVisitor::setKp, bp::arg("Kp"))
76  .def("setKd", &TaskAMEqualityPythonVisitor::setKd, bp::arg("Kd"))
77  .def("compute", &TaskAMEqualityPythonVisitor::compute,
78  bp::args("t", "q", "v", "data"))
79  .def("getConstraint", &TaskAMEqualityPythonVisitor::getConstraint)
80  .add_property("name", &TaskAMEqualityPythonVisitor::name);
81  }
82  static std::string name(TaskAM& self) {
83  std::string name = self.name();
84  return name;
85  }
86  static math::ConstraintEquality compute(TaskAM& self, const double t,
87  const Eigen::VectorXd& q,
88  const Eigen::VectorXd& v,
90  self.compute(t, q, v, data);
92  self.getConstraint().matrix(),
93  self.getConstraint().vector());
94  return cons;
95  }
96  static math::ConstraintEquality getConstraint(const TaskAM& self) {
98  self.getConstraint().matrix(),
99  self.getConstraint().vector());
100  return cons;
101  }
102  static void setReference(TaskAM& self,
103  const trajectories::TrajectorySample& ref) {
104  self.setReference(ref);
105  }
106  static const Eigen::Vector3d& getDesiredMomentumDerivative(
107  const TaskAM& self) {
108  return self.getDesiredMomentumDerivative();
109  }
110  static Eigen::Vector3d getdMomentum(TaskAM& self, const Eigen::VectorXd dv) {
111  return self.getdMomentum(dv);
112  }
113  static const Eigen::Vector3d& momentum_error(const TaskAM& self) {
114  return self.momentum_error();
115  }
116  static const Eigen::Vector3d& momentum(const TaskAM& self) {
117  return self.momentum();
118  }
119  static const Eigen::VectorXd& momentum_ref(const TaskAM& self) {
120  return self.momentum_ref();
121  }
122  static const Eigen::VectorXd& dmomentum_ref(const TaskAM& self) {
123  return self.dmomentum_ref();
124  }
125  static const Eigen::Vector3d& Kp(TaskAM& self) { return self.Kp(); }
126  static const Eigen::Vector3d& Kd(TaskAM& self) { return self.Kd(); }
127  static void setKp(TaskAM& self, const ::Eigen::VectorXd Kp) {
128  return self.Kp(Kp);
129  }
130  static void setKd(TaskAM& self, const ::Eigen::VectorXd Kv) {
131  return self.Kd(Kv);
132  }
133  static void expose(const std::string& class_name) {
134  std::string doc = "TaskAMEqualityPythonVisitor info.";
135  bp::class_<TaskAM>(class_name.c_str(), doc.c_str(), bp::no_init)
137  }
138 };
139 } // namespace python
140 } // namespace tsid
141 
142 #endif // ifndef __tsid_python_task_am_hpp__
static Eigen::Vector3d getdMomentum(TaskAM &self, const Eigen::VectorXd dv)
static const Eigen::Vector3d & getDesiredMomentumDerivative(const TaskAM &self)
static const Eigen::Vector3d & momentum_error(const TaskAM &self)
static const Eigen::VectorXd & dmomentum_ref(const TaskAM &self)
void def(const char *name, Func func)
static const Eigen::Vector3d & Kd(TaskAM &self)
static void setReference(TaskAM &self, const trajectories::TrajectorySample &ref)
data
Definition: setup.in.py:48
static void setKp(TaskAM &self, const ::Eigen::VectorXd Kp)
static math::ConstraintEquality getConstraint(const TaskAM &self)
static const Eigen::VectorXd & momentum_ref(const TaskAM &self)
static const Eigen::Vector3d & momentum(const TaskAM &self)
static std::string name(TaskAM &self)
static void expose(const std::string &class_name)
Transform3f t
static void setKd(TaskAM &self, const ::Eigen::VectorXd Kv)
static math::ConstraintEquality compute(TaskAM &self, const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, pinocchio::Data &data)
static const Eigen::Vector3d & Kp(TaskAM &self)


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