18 #ifndef __tsid_python_task_joint_bounds_hpp__ 19 #define __tsid_python_task_joint_bounds_hpp__ 32 template <
typename Task>
34 :
public boost::python::def_visitor<TaskJointBoundsPythonVisitor<Task> > {
35 template <
class PyClass>
38 cl.def(bp::init<std::string, robots::RobotWrapper&, double>(
39 (bp::arg(
"name"), bp::arg(
"robot"), bp::arg(
"Time step")),
40 "Default Constructor"))
41 .add_property(
"dim", &Task::dim,
"return dimension size")
44 .def(
"setVelocityBounds",
46 bp::args(
"lower",
"upper"))
47 .def(
"setAccelerationBounds",
49 bp::args(
"lower",
"upper"))
51 bp::args(
"t",
"q",
"v",
"data"))
54 "getAccelerationLowerBounds",
57 bp::return_value_policy<bp::copy_const_reference>()))
59 "getAccelerationUpperBounds",
62 bp::return_value_policy<bp::copy_const_reference>()))
63 .add_property(
"getVelocityLowerBounds",
66 bp::return_value_policy<bp::copy_const_reference>()))
67 .add_property(
"getVelocityUpperBounds",
70 bp::return_value_policy<bp::copy_const_reference>()))
73 static std::string
name(Task&
self) {
74 std::string
name =
self.name();
78 const Eigen::VectorXd&
q,
79 const Eigen::VectorXd&
v,
81 self.compute(t, q, v, data);
94 return self.getAccelerationLowerBounds();
97 return self.getAccelerationUpperBounds();
100 return self.getVelocityLowerBounds();
103 return self.getVelocityUpperBounds();
106 return self.setTimeStep(dt);
109 const Eigen::VectorXd upper) {
110 return self.setVelocityBounds(lower, upper);
113 const Eigen::VectorXd upper) {
114 return self.setAccelerationBounds(lower, upper);
116 static void expose(
const std::string& class_name) {
117 std::string doc =
"Task info.";
118 bp::class_<Task>(class_name.c_str(), doc.c_str(), bp::no_init)
125 #endif // ifndef __tsid_python_task_actuation_bounds_hpp__
void visit(PyClass &cl) const
static const Eigen::VectorXd & getAccelerationLowerBounds(const Task &self)
static math::ConstraintBound compute(Task &self, const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, pinocchio::Data &data)
static const Eigen::VectorXd & getVelocityUpperBounds(const Task &self)
static void setAccelerationBounds(Task &self, const Eigen::VectorXd lower, const Eigen::VectorXd upper)
void def(const char *name, Func func)
static std::string name(Task &self)
static void setTimeStep(Task &self, const double dt)
static const Eigen::VectorXd & getAccelerationUpperBounds(const Task &self)
static void expose(const std::string &class_name)
static const Eigen::VectorXd & getVelocityLowerBounds(const Task &self)
static void setVelocityBounds(Task &self, const Eigen::VectorXd lower, const Eigen::VectorXd upper)
static math::ConstraintBound getConstraint(const Task &self)