39 #include <pybind11/eigen.h> 40 #include <pybind11/pybind11.h> 41 #include <pybind11/stl.h> 46 #include <unsupported/Eigen/CXX11/Tensor> 48 #if PY_MAJOR_VERSION < 3 49 #define PY_OLDSTANDARD 52 #ifndef PY_OLDSTANDARD 53 bool PyInt_Check(PyObject* value_py) {
return PyLong_Check(value_py); }
54 long PyInt_AsLong(PyObject* value_py) {
return PyLong_AsLong(value_py); }
59 #ifndef PY_OLDSTANDARD 60 return PyUnicode_Check(value_py);
62 return PyString_Check(value_py) || PyUnicode_Check(value_py);
68 #ifndef PY_OLDSTANDARD 69 PyObject* tmp = PyUnicode_AsASCIIString(value_py);
74 return std::string(PyString_AsString(value_py));
80 #ifndef PY_OLDSTANDARD 81 return PyUnicode_DecodeASCII(value.c_str(), value.size(),
"");
83 return PyString_FromString(value.c_str());
94 #if PY_MAJOR_VERSION <= 2 95 PyObject* module = PyImport_ImportModule(
"StringIO");
96 if (!module)
ThrowPretty(
"Can't load StringIO module.");
97 PyObject* cls = PyObject_GetAttrString(module,
"StringIO");
98 if (!cls)
ThrowPretty(
"Can't load StringIO class.");
100 PyObject* module = PyImport_ImportModule(
"io");
102 PyObject* cls = PyObject_GetAttrString(module,
"BytesIO");
103 if (!cls)
ThrowPretty(
"Can't load BytesIO class.");
105 PyObject* stringio = PyObject_CallObject(cls, NULL);
106 if (!stringio)
ThrowPretty(
"Can't create StringIO object.");
112 #define ROS_MESSAGE_WRAPPER(MessageType) \ 118 struct type_caster<MessageType> \ 121 PYBIND11_TYPE_CASTER(MessageType, _("genpy.Message")); \ 123 bool load(handle src, bool) \ 125 PyObject* stringio = CreateStringIOObject(); \ 126 if (!stringio) ThrowPretty("Can't create StringIO instance."); \ 128 PyObject_CallMethod(src.ptr(), "serialize", "O", stringio); \ 129 if (!result) ThrowPretty("Can't serialize."); \ 130 result = PyObject_CallMethod(stringio, "getvalue", nullptr); \ 131 if (!result) ThrowPretty("Can't get buffer."); \ 132 char* data = PyByteArray_AsString(PyByteArray_FromObject(result)); \ 133 int len = PyByteArray_Size(result); \ 134 unsigned char* udata = new unsigned char[len]; \ 135 for (int i = 0; i < len; ++i) \ 136 udata[i] = static_cast<unsigned char>(data[i]); \ 137 ros::serialization::IStream stream(udata, len); \ 138 ros::serialization::deserialize<MessageType>(stream, value); \ 141 Py_DECREF(stringio); \ 143 return !PyErr_Occurred(); \ 146 static handle cast(MessageType src, \ 147 return_value_policy ) \ 149 ros::message_traits::DataType<MessageType::Type> type; \ 150 ThrowPretty("Can't create python object from message of type '" \ 151 << type.value() << "'!"); \ 156 #include <moveit_msgs/PlanningScene.h> 157 #include <moveit_msgs/PlanningSceneWorld.h> 166 std::pair<Initializer, Initializer>
LoadFromXML(std::string file_name,
const std::string& solver_name =
"",
const std::string& problem_name =
"",
bool parsePathAsXML =
false)
169 XMLLoader::Load(file_name, solver, problem, solver_name, problem_name, parsePathAsXML);
170 return std::pair<Initializer, Initializer>(solver, problem);
175 py::module inits = module.def_submodule(
"Initializers",
"Initializers for core EXOTica classes.");
180 const std::string full_name = i.GetName();
181 const std::string name = full_name.substr(8);
186 inits.def(
"load_xml", (
Initializer(*)(std::string,
bool)) &
XMLLoader::Load,
"Loads initializer from XML", py::arg(
"xml"), py::arg(
"parseAsXMLString") =
false);
187 inits.def(
"load_xml_full", &
LoadFromXML,
"Loads initializer from XML", py::arg(
"xml"), py::arg(
"solver_name") = std::string(
""), py::arg(
"problem_name") = std::string(
""), py::arg(
"parseAsXMLString") =
false);
198 PYBIND11_TYPE_CASTER(
Initializer, _(
"Initializer"));
207 else if (target.
GetType() ==
"int")
214 else if (PyInt_Check(value_py) || PyLong_Check(value_py))
216 target.
Set((
int)PyInt_AsLong(value_py));
220 else if (target.
GetType() ==
"long")
227 else if (PyInt_Check(value_py))
229 target.
Set(PyInt_AsLong(value_py));
234 ThrowPretty(
"to be implemented - please open an issue.");
237 else if (target.
GetType() ==
"double")
244 else if (PyFloat_Check(value_py))
246 target.
Set(PyFloat_AsDouble(value_py));
250 else if (target.
GetType() ==
"Eigen::Matrix<double, -1, 1, 0, -1, 1>")
258 target.
Set(py::cast<Eigen::VectorXd>(value_py));
262 else if (target.
GetType() ==
"Eigen::Matrix<int, -1, 1, 0, -1, 1>")
270 target.
Set(py::cast<Eigen::VectorXi>(value_py));
274 else if (target.
GetType() ==
"Eigen::Matrix<double, 2, 1, 0, 2, 1>")
282 target.
Set(py::cast<Eigen::Vector2d>(value_py));
286 else if (target.
GetType() ==
"Eigen::Matrix<double, 3, 1, 0, 3, 1>")
294 target.
Set(py::cast<Eigen::Vector3d>(value_py));
306 target.
Set(py::cast<std::vector<int>>(value_py));
318 target.
Set(py::cast<std::vector<std::string>>(value_py));
322 else if (target.
GetType() ==
"bool")
329 else if (PyBool_Check(value_py))
331 target.
Set(PyObject_IsTrue(value_py) == 1);
335 else if (target.
GetType() ==
"exotica::Initializer")
337 if (PyList_Check(value_py))
340 int n = PyList_Size(value_py);
343 if (!PyToInit(PyList_GetItem(value_py, 0), tmp))
345 WARNING(
"Could not create initializer :'(");
351 WARNING(
"List size is greater than 1 - this should not happen: " << n);
358 if (!PyToInit(value_py, tmp))
360 WARNING(
"Could not convert Python value to exotica::Initializer");
369 if (PyList_Check(value_py))
371 int n = PyList_Size(value_py);
372 std::vector<Initializer> vec(n);
373 for (
int i = 0; i < n; ++i)
375 if (!PyToInit(PyList_GetItem(value_py, i), vec[i]))
377 WARNING(
"Could not parse initializer in vector of initializers: #" << i);
386 HIGHLIGHT(
"InitializerVectorType failed PyList_Check");
399 if (!PyTuple_CheckExact(source))
405 int tuple_size = PyTuple_Size(source);
406 if (tuple_size < 1 || tuple_size > 2)
408 WARNING_NAMED(
"PyToInit",
"Wrong sized tuple for exotica::Initializer: " << tuple_size);
412 PyObject*
const name_py = PyTuple_GetItem(source, 0);
415 WARNING_NAMED(
"PyToInit",
"First element of exotica::Initializer-tuple is not a string.");
423 HIGHLIGHT(
"Unknown initializer type '" << initializer_name <<
"'");
430 PyObject*
const dict = PyTuple_GetItem(source, 1);
431 if (!PyDict_Check(dict))
433 WARNING_NAMED(
"PyToInit",
"Second element of exotica::Initializer-tuple is not a dict.");
437 PyObject *key, *value_py;
440 while (PyDict_Next(dict, &pos, &key, &value_py))
446 if (!AddPropertyFromDict(ret.
properties_.at(key_str), value_py))
448 HIGHLIGHT(
"Failed to add property '" << key_str <<
"'");
468 return PyToInit(src.ptr(), value);
473 PyObject* dict = PyDict_New();
476 addPropertyToDict(dict, prop.first, prop.second);
479 PyObject* tup = PyTuple_Pack(2, name, dict);
489 PyDict_SetItemString(dict, name.c_str(), py::cast(boost::any_cast<std::string>(prop.
Get())).ptr());
491 else if (prop.
GetType() ==
"int")
493 PyDict_SetItemString(dict, name.c_str(), py::cast(boost::any_cast<int>(prop.
Get())).ptr());
495 else if (prop.
GetType() ==
"long")
497 PyDict_SetItemString(dict, name.c_str(), py::cast(boost::any_cast<long>(prop.
Get())).ptr());
499 else if (prop.
GetType() ==
"double")
501 PyDict_SetItemString(dict, name.c_str(), py::cast(boost::any_cast<double>(prop.
Get())).ptr());
503 else if (prop.
GetType() ==
"Eigen::Matrix<double, -1, 1, 0, -1, 1>")
505 PyDict_SetItemString(dict, name.c_str(), py::cast(boost::any_cast<Eigen::VectorXd>(prop.
Get())).ptr());
507 else if (prop.
GetType() ==
"Eigen::Matrix<int, -1, 1, 0, -1, 1>")
509 PyDict_SetItemString(dict, name.c_str(), py::cast(boost::any_cast<Eigen::VectorXi>(prop.
Get())).ptr());
511 else if (prop.
GetType() ==
"Eigen::Matrix<double, 2, 1, 0, 2, 1>")
513 PyDict_SetItemString(dict, name.c_str(), py::cast(boost::any_cast<Eigen::Vector2d>(prop.
Get())).ptr());
515 else if (prop.
GetType() ==
"Eigen::Matrix<double, 3, 1, 0, 3, 1>")
517 PyDict_SetItemString(dict, name.c_str(), py::cast(boost::any_cast<Eigen::Vector3d>(prop.
Get())).ptr());
521 PyDict_SetItemString(dict, name.c_str(), py::cast(boost::any_cast<std::vector<int>>(prop.
Get())).ptr());
525 PyDict_SetItemString(dict, name.c_str(), py::cast(boost::any_cast<std::vector<std::string>>(prop.
Get())).ptr());
527 else if (prop.
GetType() ==
"bool")
529 PyDict_SetItemString(dict, name.c_str(), py::cast(boost::any_cast<bool>(prop.
Get())).ptr());
531 else if (prop.
GetType() ==
"exotica::Initializer")
533 PyObject* init = InitializerToTuple(boost::any_cast<Initializer>(prop.
Get()));
534 PyDict_SetItemString(dict, name.c_str(), init);
539 PyObject* vec = PyList_New(0);
540 for (
Initializer& i : boost::any_cast<std::vector<Initializer>>(prop.
Get()))
542 PyObject* init = InitializerToTuple(i);
543 PyList_Append(vec, init);
546 PyDict_SetItemString(dict, name.c_str(), vec);
557 return handle(InitializerToTuple(src));
565 pybind11::array_t<T> inArray)
568 pybind11::buffer_info buffer_info = inArray.request();
571 T* data =
static_cast<T*
>(buffer_info.ptr);
572 std::vector<ssize_t> shape = buffer_info.shape;
577 Eigen::TensorMap<Eigen::Tensor<T, 3, Eigen::RowMajor>> in_tensor(
578 data, shape[0], shape[1], shape[2]);
580 Hessian hessian = Hessian::Constant(shape[0], Eigen::MatrixXd::Zero(shape[1], shape[2]));
581 for (
int i = 0; i < shape[0]; i++)
583 for (
int j = 0; j < shape[1]; j++)
585 for (
int k = 0; k < shape[2]; k++)
587 hessian(i)(j, k) = in_tensor(i, j, k);
598 std::vector<ssize_t> shape(3);
599 shape[0] = inp.rows();
602 shape[1] = inp(0).rows();
603 shape[2] = inp(0).cols();
607 shape[1] = shape[2] = 0;
610 pybind11::array_t<T> array(
612 {shape[1] * shape[2] *
sizeof(T), shape[2] *
sizeof(T),
sizeof(T)});
614 Eigen::TensorMap<Eigen::Tensor<T, 3, Eigen::RowMajor>> in_tensor(
615 array.mutable_data(), shape[0], shape[1], shape[2]);
616 for (
int i = 0; i < shape[0]; i++)
618 for (
int j = 0; j < shape[1]; j++)
620 for (
int k = 0; k < shape[2]; k++)
622 in_tensor(i, j, k) = inp(i)(j, k);
626 return array.release();
642 PYBIND11_TYPE_CASTER(
Hessian, _(
"Hessian"));
651 value =
array_hessian(py::cast<pybind11::array_t<Hessian::Scalar::Scalar>>(src.ptr()));
664 return hessian_array<Hessian::Scalar::Scalar>(src);
672 module.doc() =
"Exotica Python wrapper";
674 py::class_<Setup, std::unique_ptr<Setup, py::nodelete>>
setup(module,
"Setup");
676 setup.def_static(
"get_solvers", &
Setup::GetSolvers,
"Returns a list of available solvers.");
677 setup.def_static(
"get_problems", &
Setup::GetProblems,
"Returns a list of available problems.");
678 setup.def_static(
"get_maps", &
Setup::GetMaps,
"Returns a list of available task maps.");
679 setup.def_static(
"get_collision_scenes", &
Setup::GetCollisionScenes,
"Returns a list of available collision scene plug-ins.");
680 setup.def_static(
"get_dynamics_solvers", &
Setup::GetDynamicsSolvers,
"Returns a list of available dynamics solvers plug-ins.");
686 setup.def_static(
"get_initializers", &
Setup::GetInitializers, py::return_value_policy::copy,
"Returns a list of available initializers with all available parameters/arguments.");
688 setup.def_static(
"init_ros",
689 [](
const std::string& name,
const bool&
anonymous) {
701 "Initializes an internal ROS node for publishing debug information from Exotica (i.e., activates ROS features). Options are setting the name and whether to spawn an anonymous node.",
702 py::arg(
"name") =
"exotica", py::arg(
"anonymous") =
false);
703 setup.def_static(
"load_solver", &
XMLLoader::LoadSolver,
"Instantiate solver and problem from an XML file containing both a solver and problem initializer.", py::arg(
"filepath"));
704 setup.def_static(
"load_solver_standalone", &
XMLLoader::LoadSolverStandalone,
"Instantiate only a solver from an XML file containing solely a solver initializer.", py::arg(
"filepath"));
705 setup.def_static(
"load_problem", &
XMLLoader::LoadProblem,
"Instantiate only a problem from an XML file containing solely a problem initializer.", py::arg(
"filepath"));
707 py::module tools = module.def_submodule(
"Tools");
711 tools.def(
"parse_vector", &ParseVector<double, Eigen::Dynamic>);
715 tools.def(
"load_obj", [](
const std::string& path) { Eigen::VectorXi tri; Eigen::VectorXd vert;
LoadOBJ(
LoadFile(path), tri, vert);
return py::make_tuple(tri, vert); });
726 py::arg(
"data"), py::arg(
"max_radius") = 1.0);
728 py::module sparse_costs = tools.def_submodule(
"SparseCosts")
739 py::class_<Timer, std::shared_ptr<Timer>> timer(module,
"Timer");
740 timer.def(py::init());
744 py::class_<Object, std::shared_ptr<Object>> object(module,
"Object");
745 object.def_property_readonly(
"type", &
Object::type,
"Object type");
747 object.def(
"__repr__", &
Object::Print,
"String representation of the object", py::arg(
"prepend") = std::string(
""));
751 py::enum_<TerminationCriterion>(module,
"TerminationCriterion")
763 py::enum_<RotationType>(module,
"RotationType")
772 py::enum_<BaseType>(module,
"BaseType")
773 .value(
"Fixed", BaseType::FIXED)
774 .value(
"Floating", BaseType::FLOATING)
775 .value(
"Planar", BaseType::PLANAR)
778 py::class_<KDL::Frame> kdl_frame(module,
"KDLFrame");
779 kdl_frame.def(py::init());
780 kdl_frame.def(py::init([](Eigen::MatrixXd other) {
return GetFrameFromMatrix(other); }));
781 kdl_frame.def(py::init([](Eigen::VectorXd other) {
return GetFrame(other); }));
783 kdl_frame.def(
"__repr__", [](
KDL::Frame* me) {
return "KDL::Frame " +
ToString(*me); });
789 kdl_frame.def(
"get_translation", [](
KDL::Frame* me) { Eigen::Vector3d tmp;
for (
int i = 0; i < 3; ++i) { tmp[i] = me->
p.
data[i]; }
return tmp; });
797 kdl_frame.def(
"__mul__", [](
const KDL::Frame&
A,
const KDL::Frame& B) {
return A * B; }, py::is_operator());
801 py::implicitly_convertible<Eigen::MatrixXd, KDL::Frame>();
802 py::implicitly_convertible<Eigen::VectorXd, KDL::Frame>();
804 py::class_<KDL::Vector>(module,
"KDLVector")
806 .def(py::init<double, double, double>(),
810 .def(
"x", [](
KDL::Vector& v) ->
double& {
return v[0]; })
811 .def(
"y", [](
KDL::Vector& v) ->
double& {
return v[1]; })
812 .def(
"z", [](
KDL::Vector& v) ->
double& {
return v[2]; })
815 py::class_<KDL::RotationalInertia>(module,
"KDLRotationalInertia")
816 .def(py::init<double, double, double, double, double, double>(),
825 py::class_<KDL::RigidBodyInertia>(module,
"KDLRigidBodyInertia")
826 .def(py::init<double, KDL::Vector&, KDL::RotationalInertia&>(),
832 py::class_<TaskMap, std::shared_ptr<TaskMap>,
Object>(module,
"TaskMap")
841 py::class_<TaskIndexing>(module,
"TaskIndexing")
848 py::class_<TimeIndexedTask, std::shared_ptr<TimeIndexedTask>>(module,
"TimeIndexedTask")
875 py::class_<EndPoseTask, std::shared_ptr<EndPoseTask>>(module,
"EndPoseTask")
894 py::class_<SamplingTask, std::shared_ptr<SamplingTask>>(module,
"SamplingTask")
909 py::class_<TaskSpaceVector, std::shared_ptr<TaskSpaceVector>> task_space_vector(module,
"TaskSpaceVector");
912 task_space_vector.def(
"__sub__", &TaskSpaceVector::operator-, py::is_operator());
913 task_space_vector.def(
"__repr__", [](
TaskSpaceVector* instance) {
return ((std::ostringstream&)(std::ostringstream(
"") <<
"TaskSpaceVector (" << instance->
data.transpose() <<
")")).str(); });
915 py::class_<MotionSolver, std::shared_ptr<MotionSolver>,
Object> motion_solver(module,
"MotionSolver");
920 "solve", [](std::shared_ptr<MotionSolver> sol) {
925 "Solve the problem");
928 py::class_<FeedbackMotionSolver, std::shared_ptr<FeedbackMotionSolver>,
MotionSolver> feedback_motion_solver(module,
"FeedbackMotionSolver");
931 py::class_<PlanningProblem, std::shared_ptr<PlanningProblem>,
Object>(module,
"PlanningProblem")
935 .def(
"__repr__", &
PlanningProblem::Print,
"String representation of the object", py::arg(
"prepend") = std::string(
""))
952 py::module prob = module.def_submodule(
"Problems",
"Problem types");
954 py::class_<UnconstrainedTimeIndexedProblem, std::shared_ptr<UnconstrainedTimeIndexedProblem>,
PlanningProblem> unconstrained_time_indexed_problem(prob,
"UnconstrainedTimeIndexedProblem");
977 py::class_<TimeIndexedProblem, std::shared_ptr<TimeIndexedProblem>,
PlanningProblem> time_indexed_problem(prob,
"TimeIndexedProblem");
1024 py::class_<BoundedTimeIndexedProblem, std::shared_ptr<BoundedTimeIndexedProblem>,
PlanningProblem> bounded_time_indexed_problem(prob,
"BoundedTimeIndexedProblem");
1048 py::class_<UnconstrainedEndPoseProblem, std::shared_ptr<UnconstrainedEndPoseProblem>,
PlanningProblem> unconstrained_end_pose_problem(prob,
"UnconstrainedEndPoseProblem");
1067 py::class_<EndPoseProblem, std::shared_ptr<EndPoseProblem>,
PlanningProblem> end_pose_problem(prob,
"EndPoseProblem");
1101 py::class_<BoundedEndPoseProblem, std::shared_ptr<BoundedEndPoseProblem>,
PlanningProblem> bounded_end_pose_problem(prob,
"BoundedEndPoseProblem");
1119 py::class_<SamplingProblem, std::shared_ptr<SamplingProblem>,
PlanningProblem> sampling_problem(prob,
"SamplingProblem");
1138 py::class_<TimeIndexedSamplingProblem, std::shared_ptr<TimeIndexedSamplingProblem>,
PlanningProblem> time_indexed_sampling_problem(prob,
"TimeIndexedSamplingProblem");
1158 py::enum_<ControlCostLossTermType>(module,
"ControlCostLossTermType")
1160 .value(
"Undefined", ControlCostLossTermType::Undefined)
1161 .value(
"L2", ControlCostLossTermType::L2)
1162 .value(
"SmoothL1", ControlCostLossTermType::SmoothL1)
1163 .value(
"Huber", ControlCostLossTermType::Huber)
1164 .value(
"PseudoHuber", ControlCostLossTermType::PseudoHuber)
1167 py::class_<DynamicTimeIndexedShootingProblem, std::shared_ptr<DynamicTimeIndexedShootingProblem>,
PlanningProblem>(prob,
"DynamicTimeIndexedShootingProblem")
1191 py::class_<CollisionProxy, std::shared_ptr<CollisionProxy>> collision_proxy(module,
"CollisionProxy");
1192 collision_proxy.def(py::init());
1198 collision_proxy.def_property_readonly(
"object_1", [](
CollisionProxy* instance) {
return (instance->
e1 && instance->
e2) ? instance->
e1->segment.getName() : std::string(
""); });
1199 collision_proxy.def_property_readonly(
"object_2", [](
CollisionProxy* instance) {
return (instance->
e1 && instance->
e2) ? instance->
e2->segment.getName() : std::string(
""); });
1200 collision_proxy.def_property_readonly(
"transform_1", [](
CollisionProxy* instance) {
return (instance->
e1 && instance->
e2) ? instance->
e1->frame :
KDL::Frame(); });
1201 collision_proxy.def_property_readonly(
"transform_2", [](
CollisionProxy* instance) {
return (instance->
e1 && instance->
e2) ? instance->
e2->frame :
KDL::Frame(); });
1204 py::class_<ContinuousCollisionProxy, std::shared_ptr<ContinuousCollisionProxy>> continuous_collision_proxy(module,
"ContinuousCollisionProxy");
1205 continuous_collision_proxy.def(py::init());
1210 continuous_collision_proxy.def_property_readonly(
"object_1", [](
ContinuousCollisionProxy* instance) {
return (instance->
e1 && instance->
e2) ? instance->
e1->segment.getName() : std::string(
""); });
1211 continuous_collision_proxy.def_property_readonly(
"object_2", [](
ContinuousCollisionProxy* instance) {
return (instance->
e1 && instance->
e2) ? instance->
e2->segment.getName() : std::string(
""); });
1216 py::class_<Scene, std::shared_ptr<Scene>,
Object> scene(module,
"Scene");
1223 scene.def(
"update", &
Scene::Update, py::arg(
"x"), py::arg(
"t") = 0.0);
1233 scene.def(
"get_tree_names", [](
Scene& scene) {
1234 std::vector<std::string> frame_names;
1237 frame_names.push_back(m.first);
1242 scene.def(
"set_model_state_map", (
void (
Scene::*)(
const std::map<std::string, double>&,
double,
bool)) & Scene::SetModelState, py::arg(
"x"), py::arg(
"t") = 0.0, py::arg(
"update_trajectory") =
false);
1247 scene.def(
"load_scene",
1249 py::arg(
"scene_string"),
1250 py::arg(
"offset_transform") = kdl_frame(),
1251 py::arg(
"update_collision_scene") =
true);
1252 scene.def(
"load_scene_file",
1254 py::arg(
"file_name"),
1255 py::arg(
"offset_transform") = kdl_frame(),
1256 py::arg(
"update_collision_scene") =
true);
1259 scene.def(
"is_state_valid", [](
Scene* instance,
bool self,
double safe_distance) {
return instance->
GetCollisionScene()->IsStateValid(
self, safe_distance); }, py::arg(
"check_self_collision") =
true, py::arg(
"safe_distance") = 0.0);
1260 scene.def(
"is_collision_free", [](
Scene* instance,
const std::string& o1,
const std::string& o2,
double safe_distance) {
return instance->
GetCollisionScene()->IsCollisionFree(o1, o2, safe_distance); }, py::arg(
"object_1"), py::arg(
"object_2"), py::arg(
"safe_distance") = 0.0);
1261 scene.def(
"is_allowed_to_collide", [](
Scene* instance,
const std::string& o1,
const std::string& o2,
bool self) {
return instance->
GetCollisionScene()->IsAllowedToCollide(o1, o2,
self); }, py::arg(
"object_1"), py::arg(
"object_2"), py::arg(
"check_self_collision") =
true);
1262 scene.def(
"get_collision_distance", [](
Scene* instance,
bool self) {
return instance->
GetCollisionScene()->GetCollisionDistance(
self); }, py::arg(
"check_self_collision") =
true);
1263 scene.def(
"get_collision_distance", [](
Scene* instance,
const std::string& o1,
const std::string& o2) {
return instance->
GetCollisionScene()->GetCollisionDistance(o1, o2); }, py::arg(
"object_1"), py::arg(
"object_2"));
1264 scene.def(
"get_collision_distance",
1265 [](
Scene* instance,
const std::string& o1,
const bool&
self) {
1268 py::arg(
"object_1"), py::arg(
"check_self_collision") =
true);
1269 scene.def(
"get_collision_distance",
1270 [](
Scene* instance,
const std::vector<std::string>& objects,
const bool&
self) {
1273 py::arg(
"objects"), py::arg(
"check_self_collision") =
true);
1274 scene.def(
"update_planning_scene_world",
1275 [](
Scene* instance, moveit_msgs::PlanningSceneWorld& world) {
1276 moveit_msgs::PlanningSceneWorldConstPtr my_ptr(
1277 new moveit_msgs::PlanningSceneWorld(world));
1281 scene.def(
"get_collision_robot_links", [](
Scene* instance) {
return instance->
GetCollisionScene()->GetCollisionRobotLinks(); });
1282 scene.def(
"get_collision_world_links", [](
Scene* instance) {
return instance->
GetCollisionScene()->GetCollisionWorldLinks(); });
1287 scene.def(
"attach_object_local", (
void (
Scene::*)(
const std::string& name,
const std::string& parent,
const Eigen::VectorXd& pose)) & Scene::AttachObjectLocal);
1301 scene.def(
"get_trajectory", [](
Scene* instance,
const std::string& link) {
return instance->
GetTrajectory(link)->ToString(); });
1304 scene.def(
"add_object", [](
Scene* instance,
const std::string& name,
const KDL::Frame& transform,
const std::string& parent,
const std::string& shape_resource_path,
const Eigen::Vector3d scale,
const Eigen::Vector4d color,
const bool update_collision_scene) { instance->
AddObject(name, transform, parent, shape_resource_path, scale,
KDL::RigidBodyInertia::Zero(), color, update_collision_scene); },
1307 py::arg(
"parent") =
"",
1308 py::arg(
"shape_resource_path"),
1309 py::arg(
"scale") = Eigen::Vector3d::Ones(),
1310 py::arg(
"color") = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0),
1311 py::arg(
"update_collision_scene") =
true);
1315 py::arg(
"parent") = std::string(),
1318 py::arg(
"color") = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0),
1319 py::arg(
"update_collision_scene") =
true);
1324 py::arg(
"color") = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0),
1325 py::arg(
"update_collision_scene") =
true);
1331 py::class_<CollisionScene, std::shared_ptr<CollisionScene>> collision_scene(module,
"CollisionScene");
1346 py::class_<VisualizationMoveIt> visualization_moveit(module,
"VisualizationMoveIt");
1347 visualization_moveit.def(py::init<ScenePtr>());
1349 #ifdef MSGPACK_FOUND 1350 py::class_<VisualizationMeshcat> visualization_meshcat(module,
"VisualizationMeshcat");
1351 visualization_meshcat.def(py::init<ScenePtr, const std::string&, bool, const std::string&>(), py::arg(
"scene"), py::arg(
"url"), py::arg(
"use_mesh_materials") =
true, py::arg(
"file_url") =
"");
1358 visualization_meshcat.def(
"set_property", py::overload_cast<const std::string&, const std::string&, const double&>(&
VisualizationMeshcat::SetProperty), py::arg(
"path"), py::arg(
"property"), py::arg(
"value"));
1359 visualization_meshcat.def(
"set_property", py::overload_cast<const std::string&, const std::string&, const std::string&>(&
VisualizationMeshcat::SetProperty), py::arg(
"path"), py::arg(
"property"), py::arg(
"value"));
1360 visualization_meshcat.def(
"set_property", py::overload_cast<const std::string&, const std::string&, const bool&>(&
VisualizationMeshcat::SetProperty), py::arg(
"path"), py::arg(
"property"), py::arg(
"value"));
1361 visualization_meshcat.def(
"set_property", py::overload_cast<const std::string&, const std::string&, const Eigen::Vector3d&>(&
VisualizationMeshcat::SetProperty), py::arg(
"path"), py::arg(
"property"), py::arg(
"value"));
1362 visualization_meshcat.def(
"set_property", py::overload_cast<const std::string&, const std::string&, const Eigen::Vector4d&>(&
VisualizationMeshcat::SetProperty), py::arg(
"path"), py::arg(
"property"), py::arg(
"value"));
1365 py::module kin = module.def_submodule(
"Kinematics",
"Kinematics submodule.");
1366 py::class_<KinematicTree, std::shared_ptr<KinematicTree>> kinematic_tree(kin,
"KinematicTree");
1402 kinematic_tree.def(
"set_floating_base_limits_pos_xyz_euler_zyx", (
void (
KinematicTree::*)(
const std::vector<double>&,
const std::vector<double>&,
const std::vector<double>&,
const std::vector<double>&)) & KinematicTree::SetFloatingBaseLimitsPosXYZEulerZYX);
1404 kinematic_tree.def(
"set_planar_base_limits_pos_xy_euler_z", (
void (
KinematicTree::*)(
const std::vector<double>&,
const std::vector<double>&,
const std::vector<double>&,
const std::vector<double>&)) & KinematicTree::SetPlanarBaseLimitsPosXYEulerZ);
1410 auto tree_weak_ptr = kt->
GetTree();
1411 std::vector<std::shared_ptr<KinematicElement>> tree_shared_ptr;
1412 tree_shared_ptr.reserve(tree_weak_ptr.size());
1413 for (
auto e : tree_weak_ptr)
1414 tree_shared_ptr.emplace_back(e.lock());
1415 return tree_shared_ptr;
1419 py::class_<KinematicElement, std::shared_ptr<KinematicElement>> kinematic_element(kin,
"KinematicElement");
1424 kinematic_element.def(
"get_parent_name", [](
KinematicElement* element) {
auto parent = element->
parent.lock();
if (parent) {
return parent->segment.getName(); }
else {
return std::string(
"no_parent"); } });
1438 py::class_<KinematicResponse, std::shared_ptr<KinematicResponse>> kinematic_response(kin,
"KinematicResponse");
1439 kinematic_response.def_property_readonly(
"Phi", [](
KinematicResponse* instance) {
1440 std::vector<KDL::Frame> vec;
1441 for (
unsigned int i = 0; i < instance->
Phi.cols(); ++i)
1442 vec.push_back(instance->
Phi(i));
1446 py::enum_<Integrator>(module,
"Integrator")
1447 .value(
"RK1", Integrator::RK1)
1448 .value(
"SymplecticEuler", Integrator::SymplecticEuler)
1449 .value(
"RK2", Integrator::RK2)
1450 .value(
"RK4", Integrator::RK4)
1453 py::class_<DynamicsSolver, std::shared_ptr<DynamicsSolver>,
Object>(module,
"DynamicsSolver")
1488 py::class_<shapes::Shape, shapes::ShapePtr>(module,
"Shape")
1495 py::class_<shapes::Sphere, shapes::Shape, std::shared_ptr<shapes::Sphere>>(module,
"Sphere")
1497 .def(py::init<double>())
1501 py::class_<shapes::Cylinder, shapes::Shape, std::shared_ptr<shapes::Cylinder>>(module,
"Cylinder")
1503 .def(py::init<double, double>())
1508 py::class_<shapes::Cone, shapes::Shape, std::shared_ptr<shapes::Cone>>(module,
"Cone")
1510 .def(py::init<double, double>())
1515 py::class_<shapes::Box, shapes::Shape, std::shared_ptr<shapes::Box>>(module,
"Box")
1517 .def(py::init<double, double, double>())
1520 py::class_<shapes::Plane, shapes::Shape, std::shared_ptr<shapes::Plane>>(module,
"Plane")
1522 .def(py::init<double, double, double, double>())
1530 py::class_<shapes::Mesh, shapes::Shape, std::shared_ptr<shapes::Mesh>>(module,
"Mesh")
1532 .def(py::init<unsigned int, unsigned int>())
1539 py::class_<shapes::OcTree, shapes::Shape, std::shared_ptr<shapes::OcTree>>(module,
"OcTree")
1541 .def(py::init<
const std::shared_ptr<const octomap::OcTree>&>());
1543 py::enum_<shapes::ShapeType>(module,
"ShapeType")
1544 .value(
"UNKNOWN_SHAPE", shapes::ShapeType::UNKNOWN_SHAPE)
1545 .value(
"SPHERE", shapes::ShapeType::SPHERE)
1546 .value(
"CYLINDER", shapes::ShapeType::CYLINDER)
1547 .value(
"CONE", shapes::ShapeType::CONE)
1548 .value(
"BOX", shapes::ShapeType::BOX)
1549 .value(
"PLANE", shapes::ShapeType::PLANE)
1550 .value(
"MESH", shapes::ShapeType::MESH)
1551 .value(
"OCTREE", shapes::ShapeType::OCTREE)
1554 py::enum_<ArgumentPosition>(module,
"ArgumentPosition")
1555 .value(
"ARG0", ArgumentPosition::ARG0)
1556 .value(
"ARG1", ArgumentPosition::ARG1)
1557 .value(
"ARG2", ArgumentPosition::ARG2)
1558 .value(
"ARG3", ArgumentPosition::ARG3)
1559 .value(
"ARG4", ArgumentPosition::ARG4)
1565 py::class_<BoxQPSolution>(module,
"BoxQPSolution")
1571 module.def(
"box_qp",
1572 (
BoxQPSolution(*)(
const Eigen::MatrixXd& H,
const Eigen::VectorXd& q,
1573 const Eigen::VectorXd& b_low,
const Eigen::VectorXd& b_high,
1574 const Eigen::VectorXd& x_init,
const double gamma,
1575 const int max_iterations,
const double epsilon,
const double lambda,
1576 bool use_polynomial_linesearch,
1577 bool use_cholesky_factorization)) &
1579 py::arg(
"H"), py::arg(
"q"), py::arg(
"b_low"), py::arg(
"b_high"), py::arg(
"x_init"), py::arg(
"gamma"), py::arg(
"max_iterations"), py::arg(
"epsilon"), py::arg(
"lambda"), py::arg(
"use_polynomial_linesearch") =
true, py::arg(
"use_cholesky_factorization") =
true);
1581 module.def(
"box_qp_old",
1582 (
BoxQPSolution(*)(
const Eigen::MatrixXd& H,
const Eigen::VectorXd& q,
1583 const Eigen::VectorXd& b_low,
const Eigen::VectorXd& b_high,
1584 const Eigen::VectorXd& x_init,
const double gamma,
1585 const int max_iterations,
const double epsilon,
const double lambda,
1586 bool use_polynomial_linesearch,
1587 bool use_cholesky_factorization)) &
1589 py::arg(
"H"), py::arg(
"q"), py::arg(
"b_low"), py::arg(
"b_high"), py::arg(
"x_init"), py::arg(
"gamma"), py::arg(
"max_iterations"), py::arg(
"epsilon"), py::arg(
"lambda"), py::arg(
"use_polynomial_linesearch") =
false, py::arg(
"use_cholesky_factorization") =
false);
1593 auto cleanup_exotica = []() {
1597 module.add_object(
"_cleanup", py::capsule(cleanup_exotica));
std::string GetObjectName()
PyObject * StdStringAsPy(std::string value)
void SetGoalEQ(const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0)
bool PathExists(const std::string &path)
std::shared_ptr< octomap::OcTree > LoadOctree(const std::string &file_path)
void AddTrajectory(const std::string &link, const std::string &traj)
std::vector< TaskSpaceVector > y
virtual void scaleAndPadd(double scale, double padd)=0
virtual std::vector< CollisionProxy > GetRobotToRobotCollisionDistance(double check_margin)
static std::vector< std::string > GetDynamicsSolvers()
void LoadOBJ(const std::string &data, Eigen::VectorXi &tri, Eigen::VectorXd &vert)
const Eigen::VectorXd & GetAccelerationLimits() const
void UpdateCollisionObjects()
void Update(Eigen::VectorXdRefConst u, int t)
static exotica::ScenePtr CreateScene(const Initializer &init)
Eigen::VectorXd GetTaskError(const std::string &task_name, int t) const
virtual void UpdateCollisionObjectTransforms()=0
double GetDuration() const
void Update(Eigen::VectorXdRefConst x_trajectory_in)
void SetNumberOfMaxIterations(int max_iter)
virtual Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > dStateDelta(const StateVector &x_1, const StateVector &x_2, const ArgumentPosition first_or_second)
bool GetAlwaysExternallyUpdatedCollisionScene() const
IMETHOD doubleVel diff(const doubleVel &a, const doubleVel &b, double dt=1.0)
void SetWorldLinkPadding(const double padding)
const std::set< std::string > & get_world_links_to_exclude_from_collision_scene() const
int get_num_positions() const
virtual Eigen::VectorXd ApplyStartState(bool update_traj=true)
std::vector< std::string > GetControlledJointNames()
double GetScalarTaskCost(int t) const
const bool & get_has_second_order_derivatives() const
void SetRhoEQ(const std::string &task_name, const double &rho)
double GetScalarTaskCost(const std::string &task_name) const
void SetT(const int T_in)
void SetGoalNEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
void mergeVertices(double threshold)
void SetRho(const std::string &task_name, const double &rho)
virtual Eigen::VectorXd GetFeedbackControl(Eigen::VectorXdRefConst x, int t) const =0
const std::map< std::string, std::vector< std::string > > & GetControlledJointToCollisionLinkMap() const
bool IsStateValid(Eigen::VectorXdRefConst x)
const StateDerivative & get_Fx() const
double huber_jacobian(double x, double beta)
void DisplayScene(bool use_mesh_materials=true)
bool get_has_quaternion_floating_base() const
Eigen::VectorXd GetInequality() const
const double & get_tau() const
const std::vector< std::string > & GetControlledLinkNames() const
Eigen::VectorXd GetRandomControlledState()
double ParseDouble(const std::string value)
void ResetNumberOfProblemUpdates()
void LoadSceneFile(const std::string &file_name, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
std::vector< std::string > GetModelJointNames()
std::map< std::string, shapes::ShapeType > GetCollisionObjectTypes() const
KDL::Frame GetFrameFromMatrix(Eigen::MatrixXdRefConst val)
Eigen::RowVectorXd GetScalarTaskJacobian(int t) const
double smooth_l1_cost(double x, double beta)
const Eigen::VectorXd & GetGoalState() const
double GetRho(const std::string &task_name, int t) const
std::pair< Initializer, Initializer > LoadFromXML(std::string file_name, const std::string &solver_name="", const std::string &problem_name="", bool parsePathAsXML=false)
void SetRobotLinkPadding(const double padding)
void set_X(Eigen::MatrixXdRefConst X_in)
void SetRhoNEQ(const std::string &task_name, const double rho, int t=0)
double pseudo_huber_jacobian(double x, double beta)
Eigen::VectorXd GetGoal(const std::string &task_name, int t) const
std::string GetRootFrameName()
Eigen::VectorXd GetGoal(const std::string &task_name) const
PyObject * CreateStringIOObject()
void PublishProxies(const std::vector< CollisionProxy > &proxies)
BaseType GetModelBaseType() const
shapes::ShapeConstPtr shape
std::shared_ptr< KinematicElement > FindKinematicElementByName(const std::string &frame_name)
std::string Print() const
bool AddPropertyFromDict(Property &target, PyObject *value_py)
#define WARNING_NAMED(name, x)
Eigen::MatrixXd Jacobian(std::shared_ptr< KinematicElement > element_A, const KDL::Frame &offset_a, std::shared_ptr< KinematicElement > element_B, const KDL::Frame &offset_b) const
void set_control_cost_weight(const double control_cost_weight_in)
const Eigen::MatrixXd & GetJointLimits() const
virtual ContinuousCollisionProxy ContinuousCollisionCheck(const std::string &o1, const KDL::Frame &tf1_beg, const KDL::Frame &tf1_end, const std::string &o2, const KDL::Frame &tf2_beg, const KDL::Frame &tf2_end)
int get_num_controls() const
void SetModelState(Eigen::VectorXdRefConst x, double t=0, bool update_traj=true)
Eigen::MatrixXd GetInequalityJacobian()
static std::shared_ptr< exotica::MotionSolver > CreateSolver(const std::string &type, bool prepend=true)
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
unsigned int GetNumberOfProblemUpdates() const
double GetRho(const std::string &task_name) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
StateVector Simulate(const StateVector &x, const ControlVector &u, T t)
void set_loss_type(const ControlCostLossTermType &loss_type_in)
Eigen::VectorXd GetGoalNEQ(const std::string &task_name)
void SetZero(const int n)
bool IsInitializerVectorType() const
double smooth_l1_hessian(double x, double beta)
double GetRobotLinkScale() const
int get_num_positions() const
std::weak_ptr< KinematicElement > parent
int get_num_state() const
void Update(Eigen::VectorXdRefConst x, const double &t)
std::vector< std::string > ParseList(const std::string &value, char token= ',')
std::shared_ptr< DynamicsSolver > GetDynamicsSolver() const
double GetRho(const std::string &task_name)
const ControlDerivative & get_Fu() const
Eigen::VectorXd GetGoalState() const
double GetScalarTaskCost(const std::string &task_name) const
Eigen::VectorXd GetFrameAsVector(const KDL::Frame &val, RotationType type=RotationType::RPY)
exotica::Hessian Hessian(std::shared_ptr< KinematicElement > element_A, const KDL::Frame &offset_a, std::shared_ptr< KinematicElement > element_B, const KDL::Frame &offset_b) const
Eigen::RowVectorXd GetScalarJacobian() const
double GetRho(const std::string &task_name) const
std::vector< std::string > GetKinematicChainLinks(const std::string &begin, const std::string &end) const
double GetRho(const std::string &task_name, int t=0)
static const std::string STRING_NAME
py::handle hessian_array(Hessian &inp)
Eigen::VectorXd GetControlledLinkMass() const
int get_num_velocities() const
const int & get_T() const
double smooth_l1_jacobian(double x, double beta)
void AddTrajectoryFromFile(const std::string &link, const std::string &traj)
void AddObject(const std::string &name, const KDL::Frame &transform=KDL::Frame(), const std::string &parent="", shapes::ShapeConstPtr shape=shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia &inertia=KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const bool update_collision_scene=true)
Eigen::VectorXd GetTaskError(const std::string &task_name) const
virtual StateVector F(const StateVector &x, const ControlVector &u)
Eigen::MatrixXd GetBounds() const
void LoadScene(const std::string &scene, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
int GetNumberOfMaxIterations()
std::vector< Hessian > hessian
virtual void SpecifyProblem(PlanningProblemPtr pointer)
void SetGoalEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
Eigen::VectorXd GetInequality()
const std::string & GetName() const
std::string LoadFile(const std::string &path)
Integrator get_integrator() const
std::vector< Eigen::VectorXd > rho
bool PyToInit(PyObject *source, Initializer &ret)
Eigen::VectorXd GetGoalEQ(const std::string &task_name, int t=0)
void SetRho(const std::string &task_name, const double &rho)
void RemoveObject(const std::string &name)
bool load(handle src, bool)
Eigen::MatrixXd GetStateControlCostHessian()
Eigen::VectorXd GetGoalEQ(const std::string &task_name)
Eigen::MatrixXd GetBounds() const
TerminationCriterion termination_criterion
TaskMapMap & GetTaskMaps()
int get_num_positions() const
KDL::Frame GetPose(const double &x=0.0)
Eigen::MatrixXd GetStateCostHessian(int t)
void SetSeed(const uint_fast32_t seed)
void DisplayTrajectory(Eigen::MatrixXdRefConst trajectory)
double GetRhoNEQ(const std::string &task_name)
Eigen::VectorXd GetGoalNEQ(const std::string &task_name, int t=0)
const std::vector< std::string > & GetModelLinkNames() const
const bool & HasAccelerationLimits() const
std::shared_ptr< KinematicElement > e1
void SetGoalState(Eigen::VectorXdRefConst qT)
virtual StateVector StateDelta(const StateVector &x_1, const StateVector &x_2)
void SetRhoNEQ(const std::string &task_name, const double &rho)
static void addPropertyToDict(PyObject *dict, const std::string &name, const Property &prop)
virtual int TaskSpaceJacobianDim()
int get_num_controls() const
const std::string & GetRootJointName() const
static std::vector< Initializer > GetInitializers()
std::string Print(const std::string &prepend) const override
void set_Q(Eigen::MatrixXdRefConst Q_in, int t)
void SetWorldLinkScale(const double scale)
static void InitRos(std::shared_ptr< ros::NodeHandle > nh, int numThreads=2)
const std::vector< std::weak_ptr< KinematicElement > > & GetTree() const
void SetRho(const std::string &task_name, const double rho_in, int t)
Eigen::VectorXd IdentityTransform()
Eigen::VectorXd GetNominalPose() const
void Update(Eigen::VectorXdRefConst x)
int get_num_velocities() const
void Update(Eigen::VectorXdRefConst x, int t) override
void SetJointLimitsLower(Eigen::VectorXdRefConst lower_in)
static std::shared_ptr< exotica::MotionSolver > LoadSolverStandalone(const std::string &file_name)
double GetRho(const std::string &task_name)
void UpdatePlanningSceneWorld(const moveit_msgs::PlanningSceneWorldConstPtr &world)
int get_num_state() const
struct exotica::BoxQPSolution BoxQPSolution
void SetGoalEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
const Eigen::VectorXd & GetVelocityLimits() const
unsigned int vertex_count
const std::string & getName() const
const std::string & getName() const
virtual StateVector f(const StateVector &x, const ControlVector &u)=0
std::vector< Hessian > ddPhi_dxdu
void SetJointLimitsUpper(Eigen::VectorXdRefConst upper_in)
void Update(Eigen::VectorXdRefConst x)
virtual Hessian ddStateDelta(const StateVector &x_1, const StateVector &x_2, const ArgumentPosition first_or_second)
void padd(double padding)
Eigen::VectorXd GetStateCostJacobian(int t)
int GetNumModelJoints() const
void set_U(Eigen::MatrixXdRefConst U_in)
std::vector< Eigen::MatrixXd > dPhi_dx
std::string ToString(const KDL::Frame &s)
const Eigen::Ref< const Eigen::MatrixXd > & MatrixXdRefConst
void SetRhoEQ(const std::string &task_name, const double &rho)
static std::vector< std::string > GetCollisionScenes()
Eigen::VectorXd GetGoalEQ(const std::string &task_name)
void SetAlwaysExternallyUpdatedCollisionScene(const bool value)
void SetStartTime(double t)
std::string GetType() const
std::vector< Eigen::VectorXd > ydiff
std::string GetRootJointName()
TimeIndexedTask inequality
int ParseInt(const std::string value)
void SetRho(const std::string &task_name, const double rho)
Eigen::VectorXd GetJointVelocityLimits() const
void Update(Eigen::VectorXdRefConst x, double t=0)
std::pair< std::vector< double >, std::vector< double > > GetCostEvolution() const
Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > Hessian
void set_replace_cylinders_with_capsules(const bool value)
double GetRhoEQ(const std::string &task_name, int t=0)
void SetGoalNEQ(const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0)
unsigned int triangle_count
Eigen::RowVectorXd GetScalarTransitionJacobian(int t) const
KDL::Frame FK(KinematicFrame &frame) const
virtual Eigen::Matrix< T, Eigen::Dynamic, 1 > GetPosition(Eigen::VectorXdRefConst x_in)
virtual bool isFixed() const
void set_X_star(Eigen::MatrixXdRefConst X_star_in)
Eigen::MatrixXd GetControlCostHessian(int t)
void SetRhoNEQ(const std::string &task_name, const double &rho)
void SetNominalPose(Eigen::VectorXdRefConst qNominal_in)
void SetRhoEQ(const std::string &task_name, const double rho, int t=0)
virtual void Integrate(const StateVector &x, const StateVector &dx, const double dt, StateVector &xout)
Eigen::VectorXd GetModelState()
double get_control_cost_weight() const
virtual void ComputeDerivatives(const StateVector &x, const ControlVector &u)
void DisplayState(Eigen::VectorXdRefConst state, double t=0.0)
Eigen::VectorXd GetGoalNEQ(const std::string &task_name)
static void PrintSupportedClasses()
void AddInitializers(py::module &module)
const std::vector< std::string > & GetModelJointNames() const
int GetNumberOfIterations() const
const std::string & GetRootFrameName() const
const Eigen::MatrixXd & get_Q(int t) const
void SetGoalState(Eigen::VectorXdRefConst qT)
void SetRhoEQ(const std::string &task_name, const double &rho)
void UpdateTerminalState(Eigen::VectorXdRefConst x)
Eigen::VectorXd GetGoal(const std::string &task_name)
Eigen::RowVectorXd GetScalarJacobian()
double GetRhoEQ(const std::string &task_name)
const Joint & getJoint() const
std::vector< Eigen::MatrixXd > dPhi_du
std::string Print() const
std::vector< std::string > GetKinematicChain(const std::string &begin, const std::string &end) const
std::vector< double > GetBounds()
const std::vector< std::shared_ptr< KinematicElement > > & GetModelTree() const
std::map< std::string, Initializer > known_initializers
void DetachObject(const std::string &name)
bool load(handle src, bool)
double GetScalarTransitionCost(int t) const
bool get_replace_cylinders_with_capsules() const
void SetRho(const std::string &task_name, const double &rho)
std::map< std::string, double > GetModelStateMap()
std::vector< int > ParseIntList(const std::string value)
void computeVertexNormals()
void SaveMatrix(std::string file_name, const Eigen::Ref< const Eigen::MatrixXd > mat)
std::shared_ptr< Trajectory > GetTrajectory(const std::string &link)
bool GetReplacePrimitiveShapesWithMeshes() const
void PreUpdate() override
std::map< std::string, Property > properties_
Eigen::RowVectorXd GetCostJacobian() const
static RotationalInertia Zero()
Eigen::VectorXd GetGoal(const std::string &task_name, int t=0)
static RigidBodyInertia Zero()
Eigen::MatrixXd GetBounds() const
void AttachObjectLocal(const std::string &name, const std::string &parent, const KDL::Frame &pose)
Eigen::VectorXd VectorTransform(double px=0.0, double py=0.0, double pz=0.0, double qx=0.0, double qy=0.0, double qz=0.0, double qw=1.0)
Eigen::MatrixXd GetEqualityJacobian()
virtual std::string type() const
const CollisionScenePtr & GetCollisionScene() const
void AttachObject(const std::string &name, const std::string &parent)
void SetJointAccelerationLimits(Eigen::VectorXdRefConst acceleration_in)
static std::shared_ptr< exotica::DynamicsSolver > CreateDynamicsSolver(const std::string &type, bool prepend=true)
void SetRhoNEQ(const std::string &task_name, const double &rho)
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
const ControlCostLossTermType & get_loss_type() const
Eigen::VectorXd GetGoalEQ(const std::string &task_name)
ROSLIB_DECL std::string getPath(const std::string &package_name)
int GetNumControlledJoints() const
void SetJointVelocityLimits(const Eigen::VectorXd &qdot_max_in)
double GetRhoNEQ(const std::string &task_name)
Eigen::VectorXd GetStartState() const
static std::vector< std::string > GetProblems()
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal, int t)
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0)
virtual Eigen::Vector3d GetTranslation(const std::string &name)=0
std::vector< size_t > clamped_idx
static handle cast(Hessian src, return_value_policy, handle)
double GetRhoNEQ(const std::string &task_name, int t=0)
void set_T(const int &T_in)
void UpdatePlanningScene(const moveit_msgs::PlanningScene &scene)
void computeTriangleNormals()
double GetRhoEQ(const std::string &task_name)
double huber_cost(double x, double beta)
void AddProperty(const Property &prop)
int get_num_state_derivative() const
void SetPlanarBaseLimitsPosXYEulerZ(const std::vector< double > &lower, const std::vector< double > &upper)
Eigen::VectorXd GetGoal(const std::string &task_name) const
Eigen::VectorXd GetControlCostJacobian(int t)
std::vector< double > joint_limits
double GetStateCost(int t) const
const std::vector< std::string > & GetControlledJointNames() const
std::vector< Eigen::MatrixXd > jacobian
double GetRho(const std::string &task_name) const
static const std::string STRING_NAME
std::vector< std::string > GetModelLinkNames()
const StateDerivative & get_fx() const
std::string ParsePath(const std::string &path)
double GetRobotLinkPadding() const
std::vector< std::string > GetControlledLinkNames()
const Eigen::MatrixXd & get_X_star() const
IMETHOD doubleVel addDelta(const doubleVel &a, const doubleVel &da, double dt=1.0)
void SetJointVelocityLimits(Eigen::VectorXdRefConst velocity_in)
std::map< std::string, std::weak_ptr< KinematicElement > > GetTreeMap()
std::vector< Eigen::VectorXd > GetInitialTrajectory() const
virtual std::vector< CollisionProxy > GetRobotToWorldCollisionDistance(double check_margin)
double pseudo_huber_cost(double x, double beta)
exotica::KinematicTree & GetKinematicTree()
void SetGoalNEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
virtual bool isFixed() const
Eigen::MatrixXd GetS(const std::string &task_name) const
double GetRhoNEQ(const std::string &task_name)
void SetInitialTrajectory(const std::vector< Eigen::VectorXd > &q_init_in)
Eigen::RowVectorXd GetScalarJacobian() const
std::vector< double > GetBounds()
#define ROS_MESSAGE_WRAPPER(MessageType)
double GetGoalTime() const
std::vector< TaskSpaceVector > Phi
double GetScalarCost() const
const Eigen::MatrixXd & get_X() const
std::vector< Eigen::MatrixXd > S
std::vector< Hessian > ddPhi_ddu
void SetStartState(Eigen::VectorXdRefConst x)
bool ParseBool(const std::string value)
static std::vector< std::string > GetMaps()
void Update(Eigen::VectorXdRefConst x_in, int t) override
Eigen::VectorXd GetEquality()
double GetWorldLinkScale() const
Eigen::MatrixXd GetS(const std::string &task_name, int t) const
virtual int TaskSpaceDim()=0
static std::vector< std::string > GetSolvers()
std::vector< size_t > free_idx
std::vector< Hessian > ddPhi_ddx
std::vector< TaskIndexing > indexing
Eigen::SparseMatrix< double > GetEqualityJacobian() const
Eigen::VectorXd GetGoal(const std::string &task_name) const
static std::shared_ptr< exotica::PlanningProblem > CreateProblem(const std::string &type, bool prepend=true)
PYBIND11_MODULE(_pyexotica, module)
std::shared_ptr< shapes::Shape > LoadOctreeAsShape(const std::string &file_path)
double GetDuration() const
Eigen::VectorXd GetControlledState()
static handle cast(Initializer src, return_value_policy, handle)
static std::shared_ptr< exotica::MotionSolver > LoadSolver(const std::string &file_name)
double GetStartTime() const
std::string GetTypeName(const std::type_info &type)
void Delete(const std::string &path="")
double GetControlCost(int t) const
const ControlDerivative & get_fu() const
Eigen::VectorXd GetGoal(const std::string &task_name)
virtual StateDerivative fx(const StateVector &x, const ControlVector &u)
void SetFloatingBaseLimitsPosXYZEulerZYX(const std::vector< double > &lower, const std::vector< double > &upper)
ScenePtr GetScene() const
void SetGoalEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
void SetProperty(const std::string &path, const std::string &property, const double &value)
int get_num_controls() const
Eigen::VectorXd GetRotationAsVector(const KDL::Frame &val, RotationType type)
double pseudo_huber_hessian(double x, double beta)
void PublishFrames(const std::string &tf_prefix="exotica")
void Update(Eigen::VectorXdRefConst x)
std::vector< TaskSpaceVector > Phi
static const std::string STRING_NAME
void set_integrator(Integrator integrator_in)
std::string PyAsStdString(PyObject *value_py)
std::vector< Eigen::MatrixXd > jacobian
BaseType GetControlledBaseType() const
const Eigen::MatrixXd & get_U() const
static std::shared_ptr< exotica::PlanningProblem > LoadProblem(const std::string &file_name)
const std::map< std::string, std::vector< std::string > > & GetModelLinkToCollisionLinkMap() const
std::vector< Eigen::MatrixXd > dPhi_dx
std::shared_ptr< KinematicElement > e2
int get_num_state_derivative() const
static const std::string STRING_NAME
double GetRhoEQ(const std::string &task_name)
double huber_hessian(double x, double beta)
static std::shared_ptr< Setup > Instance()
void SetRho(const std::string &task_name, const double rho, int t=0)
KDL::Frame GetFrame(Eigen::VectorXdRefConst val)
Eigen::VectorXd GetEquality() const
ControlDerivative fu_fd(const StateVector &x, const ControlVector &u)
virtual std::string Print(const std::string &prepend) const
void Update(Eigen::VectorXdRefConst x)
static void Load(std::string file_name, Initializer &solver, Initializer &problem, const std::string &solver_name="", const std::string &problem_name="", bool parsePathAsXML=false)
std::vector< TaskSpaceVector > Phi
PlanningProblemPtr GetProblem() const
double GetScalarCost() const
bool HasAttachedObject(const std::string &name)
void DisplayTrajectory(Eigen::MatrixXdRefConst trajectory, double dt=1.0)
static const std::string STRING_NAME
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
StateDerivative fx_fd(const StateVector &x, const ControlVector &u)
void SetGoalTime(const double &t)
void RemoveTrajectory(const std::string &link)
Hessian array_hessian(pybind11::array_t< T > inArray)
BoxQPSolution ExoticaBoxQP(const Eigen::MatrixXd &H, const Eigen::VectorXd &q, const Eigen::VectorXd &b_low, const Eigen::VectorXd &b_high, const Eigen::VectorXd &x_init, const double gamma, const int max_iterations, const double epsilon, const double lambda, bool use_polynomial_linesearch=false, bool use_cholesky_factorization=false)
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
const RigidBodyInertia & getInertia() const
void SetRobotLinkScale(const double scale)
std::shared_ptr< KinematicElement > e2
BoxQPSolution BoxQP(const Eigen::MatrixXd &H, const Eigen::VectorXd &q, const Eigen::VectorXd &b_low, const Eigen::VectorXd &b_high, const Eigen::VectorXd &x_init, const double th_acceptstep, const int max_iterations, const double th_gradient_tolerance, const double lambda, bool use_polynomial_linesearch=true, bool use_cholesky_factorization=true)
std::map< std::string, std::vector< double > > GetUsedJointLimits() const
std::shared_ptr< KinematicElement > e1
void AddObjectToEnvironment(const std::string &name, const KDL::Frame &transform=KDL::Frame(), shapes::ShapeConstPtr shape=nullptr, const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const bool update_collision_scene=true)
bool IsPyString(PyObject *value_py)
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
Eigen::VectorXd GetGoalNEQ(const std::string &task_name)
void SetTau(const double tau_in)
double GetScalarTaskCost(const std::string &task_name) const
void SetReplacePrimitiveShapesWithMeshes(const bool value)
Initializer CreateInitializer(const Initializer &init)
void SetRho(const std::string &task_name, const double rho_in)
static PyObject * InitializerToTuple(const Initializer &src)
double GetWorldLinkPadding() const
void SetGoalNEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
std::shared_ptr< const Shape > ShapeConstPtr
virtual ControlDerivative fu(const StateVector &x, const ControlVector &u)
Eigen::SparseMatrix< double > GetInequalityJacobian() const
int get_num_velocities() const