Skip to content

Commit

Permalink
Merge branch 'example-update' of github.com:haosulab/MPlib into examp…
Browse files Browse the repository at this point in the history
…le-update
  • Loading branch information
Lexseal committed Apr 20, 2024
2 parents 52adf0d + 8148370 commit 329fa4c
Show file tree
Hide file tree
Showing 9 changed files with 174 additions and 95 deletions.
3 changes: 1 addition & 2 deletions include/mplib/collision_detection/collision_matrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -154,8 +154,7 @@ class AllowedCollisionMatrix {
void clear();

/**
* Get sorted names of all existing elements (including
* default_entries_)
* Get sorted names of all existing elements (including ``default_entries_``)
*/
std::vector<std::string> getAllEntryNames() const;

Expand Down
41 changes: 17 additions & 24 deletions include/mplib/planning_world.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ class PlanningWorldTpl {
void addArticulation(const ArticulatedModelPtr &model, bool planned = false);

/**
* Removes the articulation with given name if exists. Updates acm_
* Removes the articulation with given name if exists. Updates ``acm_``
*
* @param name: name of the articulated model
* @return: ``true`` if success, ``false`` if articulation with given name does not
Expand Down Expand Up @@ -177,7 +177,7 @@ class PlanningWorldTpl {

/**
* Removes (and detaches) the collision object with given name if exists.
* Updates acm_
* Updates ``acm_``
*
* @param name: name of the non-articulated collision object
* @return: ``true`` if success, ``false`` if the non-articulated object
Expand Down Expand Up @@ -211,7 +211,7 @@ class PlanningWorldTpl {
* at its current pose. If the object is currently attached, disallow collision
* between the object and previous touch_links.
*
* Updates acm_ to allow collisions between attached object and touch_links.
* Updates ``acm_`` to allow collisions between attached object and touch_links.
*
* @param name: name of the non-articulated object to attach
* @param art_name: name of the planned articulation to attach to
Expand All @@ -229,10 +229,10 @@ class PlanningWorldTpl {
* sets touch_links as the name of self links that collide with the object
* in the current state.
*
* Updates acm_ to allow collisions between attached object and touch_links.
* Updates ``acm_`` to allow collisions between attached object and touch_links.
*
* If the object is already attached, the touch_links of the attached object
* is preserved and acm_ remains unchanged.
* is preserved and ``acm_`` remains unchanged.
*
* @param name: name of the non-articulated object to attach
* @param art_name: name of the planned articulation to attach to
Expand All @@ -247,7 +247,7 @@ class PlanningWorldTpl {
* at given pose. If the object is currently attached, disallow collision
* between the object and previous touch_links.
*
* Updates acm_ to allow collisions between attached object and touch_links.
* Updates ``acm_`` to allow collisions between attached object and touch_links.
*
* @param name: name of the non-articulated object to attach
* @param art_name: name of the planned articulation to attach to
Expand All @@ -266,10 +266,10 @@ class PlanningWorldTpl {
* sets touch_links as the name of self links that collide with the object
* in the current state.
*
* Updates acm_ to allow collisions between attached object and touch_links.
* Updates ``acm_`` to allow collisions between attached object and touch_links.
*
* If the object is already attached, the touch_links of the attached object
* is preserved and acm_ remains unchanged.
* is preserved and ``acm_`` remains unchanged.
*
* @param name: name of the non-articulated object to attach
* @param art_name: name of the planned articulation to attach to
Expand All @@ -284,42 +284,35 @@ class PlanningWorldTpl {
/**
* Attaches given object (w/ p_geom) to specified link of articulation at given pose.
* This is done by removing the object and then adding and attaching object.
* As a result, all previous acm_ entries with the object are removed
* As a result, all previous ``acm_`` entries with the object are removed
*
* @param name: name of the non-articulated object to attach
* @param p_geom: pointer to a CollisionGeometry object
* @param obj_geom: pointer to a CollisionGeometry object
* @param art_name: name of the planned articulation to attach to
* @param link_id: index of the link of the planned articulation to attach to
* @param pose: attached pose (relative pose from attached link to object)
* @param touch_links: link names that the attached object touches
*/
void attachObject(const std::string &name, const CollisionGeometryPtr &p_geom,
void attachObject(const std::string &name, const CollisionGeometryPtr &obj_geom,
const std::string &art_name, int link_id, const Pose<S> &pose,
const std::vector<std::string> &touch_links);

/**
* Attaches given object (w/ p_geom) to specified link of articulation at given pose.
* This is done by removing the object and then adding and attaching object.
* As a result, all previous acm_ entries with the object are removed.
* As a result, all previous ``acm_`` entries with the object are removed.
* Automatically sets touch_links as the name of self links
* that collide with the object in the current state (auto touch_links).
*
* @param name: name of the non-articulated object to attach
* @param p_geom: pointer to a CollisionGeometry object
* @param obj_geom: pointer to a CollisionGeometry object
* @param art_name: name of the planned articulation to attach to
* @param link_id: index of the link of the planned articulation to attach to
* @param pose: attached pose (relative pose from attached link to object)
*/
void attachObject(const std::string &name, const CollisionGeometryPtr &p_geom,
void attachObject(const std::string &name, const CollisionGeometryPtr &obj_geom,
const std::string &art_name, int link_id, const Pose<S> &pose);

/**
* Attaches the object the articulation is currently touching
*
* @param art_name name of the planned articulation to attach to
*/
void attachCurrentlyTouchingObject(const std::string &art_name);

/**
* Attaches given sphere to specified link of articulation (auto touch_links)
*
Expand Down Expand Up @@ -356,7 +349,7 @@ class PlanningWorldTpl {

/**
* Detaches object with given name.
* Updates acm_ to disallow collision between the object and touch_links.
* Updates ``acm_`` to disallow collision between the object and touch_links.
*
* @param name: name of the non-articulated object to detach
* @param also_remove: whether to also remove object from world
Expand All @@ -366,8 +359,8 @@ class PlanningWorldTpl {
bool detachObject(const std::string &name, bool also_remove = false);

/**
* Detaches all attached objects. Updates acm_ to disallow collision between
* the object and touch_links.
* Detaches all attached objects.
* Updates ``acm_`` to disallow collision between the object and touch_links.
*
* @param also_remove: whether to also remove objects from world
* @return: ``true`` if success, ``false`` if there are no attached objects
Expand Down
40 changes: 24 additions & 16 deletions mplib/pymp/__init__.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -420,7 +420,7 @@ class PlanningWorld:
its current pose. If the object is currently attached, disallow collision
between the object and previous touch_links.
Updates acm_ to allow collisions between attached object and touch_links.
Updates ``acm_`` to allow collisions between attached object and touch_links.
:param name: name of the non-articulated object to attach
:param art_name: name of the planned articulation to attach to
Expand All @@ -437,10 +437,10 @@ class PlanningWorld:
touch_links as the name of self links that collide with the object in the
current state.
Updates acm_ to allow collisions between attached object and touch_links.
Updates ``acm_`` to allow collisions between attached object and touch_links.
If the object is already attached, the touch_links of the attached object is
preserved and acm_ remains unchanged.
preserved and ``acm_`` remains unchanged.
:param name: name of the non-articulated object to attach
:param art_name: name of the planned articulation to attach to
Expand All @@ -457,7 +457,7 @@ class PlanningWorld:
given pose. If the object is currently attached, disallow collision between the
object and previous touch_links.
Updates acm_ to allow collisions between attached object and touch_links.
Updates ``acm_`` to allow collisions between attached object and touch_links.
:param name: name of the non-articulated object to attach
:param art_name: name of the planned articulation to attach to
Expand All @@ -475,10 +475,10 @@ class PlanningWorld:
touch_links as the name of self links that collide with the object in the
current state.
Updates acm_ to allow collisions between attached object and touch_links.
Updates ``acm_`` to allow collisions between attached object and touch_links.
If the object is already attached, the touch_links of the attached object is
preserved and acm_ remains unchanged.
preserved and ``acm_`` remains unchanged.
:param name: name of the non-articulated object to attach
:param art_name: name of the planned articulation to attach to
Expand All @@ -491,7 +491,7 @@ class PlanningWorld:
def attach_object(
self,
name: str,
p_geom: collision_detection.fcl.CollisionGeometry,
obj_geom: collision_detection.fcl.CollisionGeometry,
art_name: str,
link_id: int,
pose: Pose,
Expand All @@ -500,10 +500,10 @@ class PlanningWorld:
"""
Attaches given object (w/ p_geom) to specified link of articulation at given
pose. This is done by removing the object and then adding and attaching object.
As a result, all previous acm_ entries with the object are removed
As a result, all previous ``acm_`` entries with the object are removed
:param name: name of the non-articulated object to attach
:param p_geom: pointer to a CollisionGeometry object
:param obj_geom: pointer to a CollisionGeometry object
:param art_name: name of the planned articulation to attach to
:param link_id: index of the link of the planned articulation to attach to
:param pose: attached pose (relative pose from attached link to object)
Expand All @@ -513,20 +513,20 @@ class PlanningWorld:
def attach_object(
self,
name: str,
p_geom: collision_detection.fcl.CollisionGeometry,
obj_geom: collision_detection.fcl.CollisionGeometry,
art_name: str,
link_id: int,
pose: Pose,
) -> None:
"""
Attaches given object (w/ p_geom) to specified link of articulation at given
pose. This is done by removing the object and then adding and attaching object.
As a result, all previous acm_ entries with the object are removed.
As a result, all previous ``acm_`` entries with the object are removed.
Automatically sets touch_links as the name of self links that collide with the
object in the current state (auto touch_links).
:param name: name of the non-articulated object to attach
:param p_geom: pointer to a CollisionGeometry object
:param obj_geom: pointer to a CollisionGeometry object
:param art_name: name of the planned articulation to attach to
:param link_id: index of the link of the planned articulation to attach to
:param pose: attached pose (relative pose from attached link to object)
Expand Down Expand Up @@ -572,10 +572,18 @@ class PlanningWorld:
:param request: collision request params.
:return: List of ``WorldCollisionResult`` objects
"""
def detach_all_objects(self, also_remove: bool = False) -> bool:
"""
Detaches all attached objects. Updates ``acm_`` to disallow collision between
the object and touch_links.
:param also_remove: whether to also remove objects from world
:return: ``True`` if success, ``False`` if there are no attached objects
"""
def detach_object(self, name: str, also_remove: bool = False) -> bool:
"""
Detaches object with given name. Updates acm_ to disallow collision between the
object and touch_links.
Detaches object with given name. Updates ``acm_`` to disallow collision between
the object and touch_links.
:param name: name of the non-articulated object to detach
:param also_remove: whether to also remove object from world
Expand Down Expand Up @@ -714,7 +722,7 @@ class PlanningWorld:
"""
def remove_articulation(self, name: str) -> bool:
"""
Removes the articulation with given name if exists. Updates acm_
Removes the articulation with given name if exists. Updates ``acm_``
:param name: name of the articulated model
:return: ``True`` if success, ``False`` if articulation with given name does not
Expand All @@ -723,7 +731,7 @@ class PlanningWorld:
def remove_object(self, name: str) -> bool:
"""
Removes (and detaches) the collision object with given name if exists. Updates
acm_
``acm_``
:param name: name of the non-articulated collision object
:return: ``True`` if success, ``False`` if the non-articulated object with given
Expand Down
2 changes: 1 addition & 1 deletion mplib/pymp/collision_detection/__init__.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class AllowedCollisionMatrix:
"""
def get_all_entry_names(self) -> list[str]:
"""
Get sorted names of all existing elements (including default_entries_)
Get sorted names of all existing elements (including ``default_entries_``)
"""
def get_allowed_collision(self, name1: str, name2: str) -> AllowedCollision | None:
"""
Expand Down
95 changes: 95 additions & 0 deletions mplib/sapien_utils/conversion.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
Box,
BVHModel,
Capsule,
CollisionGeometry,
CollisionObject,
Convex,
Cylinder,
Expand Down Expand Up @@ -287,6 +288,100 @@ def _get_collision_obj(
"(The scene might have changed since last update)"
)

def attach_object( # type: ignore
self,
obj: Entity | str,
articulation: PhysxArticulation | str,
link: PhysxArticulationLinkComponent | int,
*,
pose: Optional[Pose] = None,
touch_links: Optional[list[PhysxArticulationLinkComponent | str]] = None,
obj_geom: Optional[CollisionGeometry] = None,
) -> None:
"""
Attaches given non-articulated object to the specified link of articulation.
Updates ``acm_`` to allow collisions between attached object and touch_links.
:param obj: the non-articulated object (or its name) to attach
:param articulation: the planned articulation (or its name) to attach to
:param link: the link of the planned articulation (or its index) to attach to
:param pose: attached pose (relative pose from attached link to object).
If ``None``, attach the object at its current pose.
:param touch_links: links (or their names) that the attached object touches.
When ``None``,
* if the object is not currently attached, touch_links are set to the name
of articulation links that collide with the object in the current state.
* if the object is already attached, touch_links of the attached object
is preserved and ``acm_`` remains unchanged.
:param obj_geom: a CollisionGeometry object representing the attached object.
If not ``None``, pose must be not ``None``.
.. raw:: html
<details>
<summary><a>Overloaded
<code class="docutils literal notranslate">
<span class="pre">PlanningWorld.attach_object()</span>
</code>
methods</a></summary>
.. automethod:: mplib.PlanningWorld.attach_object
.. raw:: html
</details>
"""
kwargs = {"name": obj, "art_name": articulation, "link_id": link}
if pose is not None:
kwargs["pose"] = pose
if touch_links is not None:
kwargs["touch_links"] = [
l.name if isinstance(l, PhysxArticulationLinkComponent) else l
for l in touch_links # noqa: E741
]
if obj_geom is not None:
kwargs["obj_geom"] = obj_geom

if isinstance(obj, Entity):
kwargs["name"] = convert_object_name(obj)
if isinstance(articulation, PhysxArticulation):
kwargs["art_name"] = articulation = convert_object_name(articulation)
if isinstance(link, PhysxArticulationLinkComponent):
kwargs["link_id"] = (
self.get_articulation(articulation)
.get_pinocchio_model()
.get_link_names()
.index(link.name)
)

super().attach_object(**kwargs)

def detach_object(self, obj: Entity | str, also_remove: bool = False) -> bool: # type: ignore
"""
Detaches the given object.
Updates ``acm_`` to disallow collision between the object and touch_links.
:param obj: the non-articulated object (or its name) to detach
:param also_remove: whether to also remove the object from PlanningWorld
:return: ``True`` if success, ``False`` if the given object is not attached.
.. raw:: html
<details>
<summary><a>Overloaded
<code class="docutils literal notranslate">
<span class="pre">PlanningWorld.detach_object()</span>
</code>
method</a></summary>
.. automethod:: mplib.PlanningWorld.detach_object
.. raw:: html
</details>
"""
if isinstance(obj, Entity):
obj = convert_object_name(obj)
return super().detach_object(obj, also_remove=also_remove)

@staticmethod
def convert_physx_component(comp: PhysxRigidBaseComponent) -> FCLObject | None:
"""
Expand Down
2 changes: 1 addition & 1 deletion pybind/docstring/collision_detection/collision_matrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ Clear all data in the allowed collision matrix)doc";

static const char *__doc_mplib_collision_detection_AllowedCollisionMatrix_getAllEntryNames =
R"doc(
Get sorted names of all existing elements (including default_entries_))doc";
Get sorted names of all existing elements (including ``default_entries_``))doc";

static const char *__doc_mplib_collision_detection_AllowedCollisionMatrix_getAllowedCollision =
R"doc(
Expand Down
Loading

0 comments on commit 329fa4c

Please sign in to comment.