Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add more Python bindings for collision and dynamics #1545

Merged
merged 3 commits into from
Apr 2, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,10 @@ set(required_libraries
)

if(DART_IN_SOURCE_BUILD)
dart_build_example_in_source(${example_name}
LINK_LIBRARIES ${required_libraries}
COMPILE_FEATURES cxx_std_14
)
endif()
dart_build_example_in_source(${example_name}
LINK_LIBRARIES ${required_libraries}
COMPILE_FEATURES cxx_std_14
)
return()
endif()

Expand Down
13 changes: 12 additions & 1 deletion python/dartpy/collision/CollisionFilter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,18 @@ void CollisionFilter(py::module& m)
+[](dart::collision::BodyNodeCollisionFilter* self) {
self->removeAllBodyNodePairsFromBlackList();
},
"Remove all the BodyNode pairs from the blacklist.");
"Remove all the BodyNode pairs from the blacklist.")
.def(
"ignoresCollision",
+[](const dart::collision::BodyNodeCollisionFilter* self,
const dart::collision::CollisionObject* object1,
const dart::collision::CollisionObject* object2) -> bool {
return self->ignoresCollision(object1, object2);
},
::py::arg("object1"),
::py::arg("object2"),
"Returns true if the given two CollisionObjects should be checked by "
"the collision detector, false otherwise.");
}

} // namespace python
Expand Down
59 changes: 9 additions & 50 deletions python/dartpy/collision/CollisionGroup.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,48 +180,17 @@ void CollisionGroup(py::module& m)
+[](const dart::collision::CollisionGroup* self) -> std::size_t {
return self->getNumShapeFrames();
})
.def(
"collide",
+[](dart::collision::CollisionGroup* self) -> bool {
return self->collide();
},
"Performs collision check within this CollisionGroup")
.def(
"collide",
+[](dart::collision::CollisionGroup* self,
const dart::collision::CollisionOption& option) -> bool {
return self->collide(option);
},
::py::arg("option"),
"Performs collision check within this CollisionGroup")
.def(
"collide",
+[](dart::collision::CollisionGroup* self,
const dart::collision::CollisionOption& option,
dart::collision::CollisionResult* result) -> bool {
return self->collide(option, result);
},
::py::arg("option"),
::py::arg("result"),
::py::arg("option")
= dart::collision::CollisionOption(false, 1u, nullptr),
::py::arg("result") = nullptr,
"Performs collision check within this CollisionGroup")
.def(
"collide",
+[](dart::collision::CollisionGroup* self,
dart::collision::CollisionGroup* otherGroup) -> bool {
return self->collide(otherGroup);
},
::py::arg("otherGroup"),
"Perform collision check against other CollisionGroup")
.def(
"collide",
+[](dart::collision::CollisionGroup* self,
dart::collision::CollisionGroup* otherGroup,
const dart::collision::CollisionOption& option) -> bool {
return self->collide(otherGroup, option);
},
::py::arg("otherGroup"),
::py::arg("option"),
"Perform collision check against other CollisionGroup")
.def(
"collide",
+[](dart::collision::CollisionGroup* self,
Expand All @@ -231,30 +200,20 @@ void CollisionGroup(py::module& m)
return self->collide(otherGroup, option, result);
},
::py::arg("otherGroup"),
::py::arg("option"),
::py::arg("result"),
::py::arg("option")
= dart::collision::CollisionOption(false, 1u, nullptr),
::py::arg("result") = nullptr,
"Perform collision check against other CollisionGroup")
.def(
"distance",
+[](dart::collision::CollisionGroup* self) -> double {
return self->distance();
})
.def(
"distance",
+[](dart::collision::CollisionGroup* self,
const dart::collision::DistanceOption& option) -> double {
return self->distance(option);
},
::py::arg("option"))
.def(
"distance",
+[](dart::collision::CollisionGroup* self,
const dart::collision::DistanceOption& option,
dart::collision::DistanceResult* result) -> double {
return self->distance(option, result);
},
::py::arg("option"),
::py::arg("result"))
::py::arg("option")
= dart::collision::DistanceOption(false, 0.0, nullptr),
::py::arg("result") = nullptr)
.def(
"raycast",
+[](dart::collision::CollisionGroup* self,
Expand Down
6 changes: 2 additions & 4 deletions python/dartpy/collision/module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ namespace python {
void Contact(py::module& sm);

void CollisionFilter(py::module& sm);
void CollisionObject(py::module& sm);
void CollisionOption(py::module& sm);
void CollisionResult(py::module& sm);

Expand All @@ -58,8 +59,6 @@ void CollisionGroup(py::module& sm);
void FCLCollisionGroup(py::module& sm);
void DARTCollisionGroup(py::module& sm);

void CollisionObject(py::module& sm);

#if HAVE_BULLET
void BulletCollisionDetector(py::module& sm);
void BulletCollisionGroup(py::module& sm);
Expand All @@ -77,6 +76,7 @@ void dart_collision(py::module& m)
Contact(sm);

CollisionFilter(sm);
CollisionObject(sm);
CollisionOption(sm);
CollisionResult(sm);

Expand All @@ -94,8 +94,6 @@ void dart_collision(py::module& m)
FCLCollisionGroup(sm);
DARTCollisionGroup(sm);

CollisionObject(sm);

#if HAVE_BULLET
BulletCollisionDetector(sm);
BulletCollisionGroup(sm);
Expand Down
6 changes: 6 additions & 0 deletions python/dartpy/dynamics/Node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@

#include <dart/dart.hpp>
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>
#include "eigen_geometry_pybind.h"
#include "eigen_pybind.h"
#include "pointers.hpp"
Expand Down Expand Up @@ -96,6 +97,11 @@ void Node(py::module& m)
-> dart::dynamics::ConstBodyNodePtr {
return self->getBodyNodePtr();
})
.def(
"getBodyNode",
+[](dart::dynamics::Node* self) -> dart::dynamics::BodyNode* {
return self->getBodyNodePtr().get();
})
.def(
"isRemoved",
+[](const dart::dynamics::Node* self) -> bool {
Expand Down
1 change: 1 addition & 0 deletions python/dartpy/dynamics/ShapeNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ void ShapeNode(py::module& m)
dart::dynamics::ShapeNode,
dart::dynamics::JacobianNode,
dart::dynamics::ShapeFrame,
dart::dynamics::Node,
std::shared_ptr<dart::dynamics::ShapeNode>>(m, "ShapeNode")
.def(
"setProperties",
Expand Down