-
Notifications
You must be signed in to change notification settings - Fork 5
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Moved collision velocity contraint outside the pyopensot.cpp file in …
…order to make the bindings compile when the flag OPENSOT_COMPILE_COLLISION is False. Collisions bindngs are now in pyopensot_collision python lib.
- Loading branch information
1 parent
50ce7e9
commit 4dbd5be
Showing
5 changed files
with
73 additions
and
40 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,31 @@ | ||
#include <pybind11/pybind11.h> | ||
#include <pybind11/eigen.h> | ||
#include <pybind11/stl.h> | ||
#include <OpenSoT/constraints/velocity/CollisionAvoidance.h> | ||
|
||
|
||
namespace py = pybind11; | ||
using namespace OpenSoT::constraints::velocity; | ||
|
||
void pyVelocityCollisionAvoidance(py::module& m) { | ||
py::class_<CollisionAvoidance, std::shared_ptr<CollisionAvoidance>, OpenSoT::Constraint<Eigen::MatrixXd, Eigen::VectorXd>>(m, "CollisionAvoidance") | ||
.def(py::init<const XBot::ModelInterface&, int, urdf::ModelConstSharedPtr, srdf::ModelConstSharedPtr>(), | ||
py::arg(), py::arg("max_pairs") = -1, py::arg("collision_urdf") = nullptr, py::arg("collision_srdf") = nullptr) | ||
.def("getLinkPairThreshold", &CollisionAvoidance::getLinkPairThreshold) | ||
.def("getDetectionThreshold", &CollisionAvoidance::getDetectionThreshold) | ||
.def("setLinkPairThreshold", &CollisionAvoidance::setLinkPairThreshold) | ||
.def("setDetectionThreshold", &CollisionAvoidance::setDetectionThreshold) | ||
.def("update", &CollisionAvoidance::update) | ||
.def("setMaxPairs", &CollisionAvoidance::setMaxPairs) | ||
.def("setCollisionList", &CollisionAvoidance::setCollisionList) | ||
.def("collisionModelUpdated", &CollisionAvoidance::collisionModelUpdated) | ||
.def("addCollisionShape", &CollisionAvoidance::addCollisionShape) | ||
.def("moveCollisionShape", &CollisionAvoidance::moveCollisionShape) | ||
.def("setBoundScaling", &CollisionAvoidance::setBoundScaling) | ||
.def("setLinksVsEnvironment", &CollisionAvoidance::setLinksVsEnvironment) | ||
.def("getCollisionModel", (const XBot::Collision::CollisionModel& (CollisionAvoidance::*)() const) &CollisionAvoidance::getCollisionModel) | ||
.def("getOrderedWitnessPointVector", &CollisionAvoidance::getOrderedWitnessPointVector) | ||
.def("getOrderedLinkPairVector", &CollisionAvoidance::getOrderedLinkPairVector) | ||
.def("getOrderedDistanceVector", &CollisionAvoidance::getOrderedDistanceVector) | ||
.def("getCollisionJacobian", &CollisionAvoidance::getCollisionJacobian); | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,7 @@ | ||
#include "constraints/velocity_collision.hpp" | ||
|
||
PYBIND11_MODULE(pyopensot_collision, m) { | ||
auto m_c = m.def_submodule("constraints"); | ||
auto m_cv = m_c.def_submodule("velocity"); | ||
pyVelocityCollisionAvoidance(m_cv); | ||
} |