bindings/python/tasks/task-se3-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_se3_hpp__
19 #define __tsid_python_task_se3_hpp__
20 
22 
28 namespace tsid {
29 namespace python {
30 namespace bp = boost::python;
31 
32 template <typename TaskSE3>
34  : public boost::python::def_visitor<
35  TaskSE3EqualityPythonVisitor<TaskSE3> > {
36  template <class PyClass>
37 
38  void visit(PyClass& cl) const {
39  cl.def(bp::init<std::string, robots::RobotWrapper&, std::string>(
40  (bp::arg("name"), bp::arg("robot"), bp::arg("framename")),
41  "Default Constructor"))
42  .add_property("dim", &TaskSE3::dim, "return dimension size")
43  .def("setReference", &TaskSE3EqualityPythonVisitor::setReference,
44  bp::arg("ref"))
45  .add_property("getDesiredAcceleration",
46  bp::make_function(
48  bp::return_value_policy<bp::copy_const_reference>()),
49  "Return Acc_desired")
50  .def("getAcceleration", &TaskSE3EqualityPythonVisitor::getAcceleration,
51  bp::arg("dv"))
52  .add_property("position_error",
53  bp::make_function(
55  bp::return_value_policy<bp::copy_const_reference>()))
56  .add_property("velocity_error",
57  bp::make_function(
59  bp::return_value_policy<bp::copy_const_reference>()))
60  .add_property("position",
61  bp::make_function(
63  bp::return_value_policy<bp::copy_const_reference>()))
64  .add_property("velocity",
65  bp::make_function(
67  bp::return_value_policy<bp::copy_const_reference>()))
68  .add_property("position_ref",
69  bp::make_function(
71  bp::return_value_policy<bp::copy_const_reference>()))
72  .add_property("velocity_ref",
73  bp::make_function(
75  bp::return_value_policy<bp::copy_const_reference>()))
76  .add_property("Kp",
77  bp::make_function(
79  bp::return_value_policy<bp::copy_const_reference>()))
80  .add_property("Kd",
81  bp::make_function(
83  bp::return_value_policy<bp::copy_const_reference>()))
84  .def("setKp", &TaskSE3EqualityPythonVisitor::setKp, bp::arg("Kp"))
85  .def("setKd", &TaskSE3EqualityPythonVisitor::setKd, bp::arg("Kd"))
86  .def("useLocalFrame", &TaskSE3EqualityPythonVisitor::useLocalFrame,
87  bp::arg("local_frame"))
88  .add_property("mask",
89  bp::make_function(
91  bp::return_value_policy<bp::copy_const_reference>()),
92  "Return mask")
93  .def("setMask", &TaskSE3EqualityPythonVisitor::setMask, bp::arg("mask"))
95  bp::args("t", "q", "v", "data"))
96  .def("getConstraint", &TaskSE3EqualityPythonVisitor::getConstraint)
97  .add_property("frame_id", &TaskSE3::frame_id, "frame id return")
98  .add_property("name", &TaskSE3EqualityPythonVisitor::name);
99  }
100  static std::string name(TaskSE3& self) {
101  std::string name = self.name();
102  return name;
103  }
104  static math::ConstraintEquality compute(TaskSE3& self, const double t,
105  const Eigen::VectorXd& q,
106  const Eigen::VectorXd& v,
108  self.compute(t, q, v, data);
110  self.getConstraint().matrix(),
111  self.getConstraint().vector());
112  return cons;
113  }
114  static math::ConstraintEquality getConstraint(const TaskSE3& self) {
116  self.getConstraint().matrix(),
117  self.getConstraint().vector());
118  return cons;
119  }
120  static void setReference(TaskSE3& self, trajectories::TrajectorySample& ref) {
121  self.setReference(ref);
122  }
123  static const Eigen::VectorXd& getDesiredAcceleration(const TaskSE3& self) {
124  return self.getDesiredAcceleration();
125  }
126  static Eigen::VectorXd getAcceleration(TaskSE3& self,
127  const Eigen::VectorXd dv) {
128  return self.getAcceleration(dv);
129  }
130  static const Eigen::VectorXd& position_error(const TaskSE3& self) {
131  return self.position_error();
132  }
133  static const Eigen::VectorXd& velocity_error(const TaskSE3& self) {
134  return self.velocity_error();
135  }
136  static const Eigen::VectorXd& position(const TaskSE3& self) {
137  return self.position();
138  }
139  static const Eigen::VectorXd& velocity(const TaskSE3& self) {
140  return self.velocity();
141  }
142  static const Eigen::VectorXd& position_ref(const TaskSE3& self) {
143  return self.position_ref();
144  }
145  static const Eigen::VectorXd& velocity_ref(const TaskSE3& self) {
146  return self.velocity_ref();
147  }
148  static const Eigen::VectorXd& Kp(TaskSE3& self) { return self.Kp(); }
149  static const Eigen::VectorXd& Kd(TaskSE3& self) { return self.Kd(); }
150  static void setKp(TaskSE3& self, const ::Eigen::VectorXd Kp) {
151  return self.Kp(Kp);
152  }
153  static void setKd(TaskSE3& self, const ::Eigen::VectorXd Kv) {
154  return self.Kd(Kv);
155  }
156  static void useLocalFrame(TaskSE3& self, const bool local_frame) {
157  self.useLocalFrame(local_frame);
158  }
159  static void getMask(TaskSE3& self) { self.getMask(); }
160  static void setMask(TaskSE3& self, const ::Eigen::VectorXd mask) {
161  self.setMask(mask);
162  }
163  static Eigen::VectorXd frame_id(TaskSE3& self) { return self.frame_id(); }
164  static void expose(const std::string& class_name) {
165  std::string doc = "TaskSE3 info.";
166  bp::class_<TaskSE3>(class_name.c_str(), doc.c_str(), bp::no_init)
168 
169  // bp::register_ptr_to_python< boost::shared_ptr<math::ConstraintBase> >();
170  }
171 };
172 } // namespace python
173 } // namespace tsid
174 
175 #endif // ifndef __tsid_python_task_se3_hpp__
static const Eigen::VectorXd & position(const TaskSE3 &self)
static Eigen::VectorXd getAcceleration(TaskSE3 &self, const Eigen::VectorXd dv)
static const Eigen::VectorXd & velocity_error(const TaskSE3 &self)
static void setMask(TaskSE3 &self, const ::Eigen::VectorXd mask)
void def(const char *name, Func func)
data
Definition: setup.in.py:48
static void setKd(TaskSE3 &self, const ::Eigen::VectorXd Kv)
static void useLocalFrame(TaskSE3 &self, const bool local_frame)
static const Eigen::VectorXd & velocity_ref(const TaskSE3 &self)
static const Eigen::VectorXd & position_error(const TaskSE3 &self)
static const Eigen::VectorXd & position_ref(const TaskSE3 &self)
static void setReference(TaskSE3 &self, trajectories::TrajectorySample &ref)
static math::ConstraintEquality compute(TaskSE3 &self, const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, pinocchio::Data &data)
Transform3f t
static void setKp(TaskSE3 &self, const ::Eigen::VectorXd Kp)
static const Eigen::VectorXd & getDesiredAcceleration(const TaskSE3 &self)
static math::ConstraintEquality getConstraint(const TaskSE3 &self)
static const Eigen::VectorXd & velocity(const TaskSE3 &self)


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