Skip to content

Commit

Permalink
Rename p_geom to obj_geom in PlanningWorld::attachObject
Browse files Browse the repository at this point in the history
  • Loading branch information
KolinGuo committed Apr 20, 2024
1 parent 693745a commit ab696c0
Show file tree
Hide file tree
Showing 5 changed files with 19 additions and 18 deletions.
8 changes: 4 additions & 4 deletions include/mplib/planning_world.h
Original file line number Diff line number Diff line change
Expand Up @@ -287,13 +287,13 @@ class PlanningWorldTpl {
* 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);

Expand All @@ -305,12 +305,12 @@ class PlanningWorldTpl {
* 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);

/**
Expand Down
8 changes: 4 additions & 4 deletions mplib/pymp/__init__.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -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 @@ -503,7 +503,7 @@ class PlanningWorld:
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,7 +513,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 @@ -526,7 +526,7 @@ class PlanningWorld:
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
4 changes: 2 additions & 2 deletions pybind/docstring/planning_world.h
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ 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
: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 @@ -181,7 +181,7 @@ 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))doc";
Expand Down
9 changes: 5 additions & 4 deletions pybind/pybind_planning_world.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,15 +103,16 @@ void build_pyplanning_world(py::module &pymp) {
const std::string &, int, const Pose<S> &,
const std::vector<std::string> &>(
&PlanningWorld::attachObject),
py::arg("name"), py::arg("p_geom"), py::arg("art_name"), py::arg("link_id"),
py::arg("pose"), py::arg("touch_links"),
py::arg("name"), py::arg("obj_geom"), py::arg("art_name"),
py::arg("link_id"), py::arg("pose"), py::arg("touch_links"),
DOC(mplib, PlanningWorldTpl, attachObject, 5))
.def("attach_object",
py::overload_cast<const std::string &, const CollisionGeometryPtr &,
const std::string &, int, const Pose<S> &>(
&PlanningWorld::attachObject),
py::arg("name"), py::arg("p_geom"), py::arg("art_name"), py::arg("link_id"),
py::arg("pose"), DOC(mplib, PlanningWorldTpl, attachObject, 6))
py::arg("name"), py::arg("obj_geom"), py::arg("art_name"),
py::arg("link_id"), py::arg("pose"),
DOC(mplib, PlanningWorldTpl, attachObject, 6))
.def("attach_sphere", &PlanningWorld::attachSphere, py::arg("radius"),
py::arg("art_name"), py::arg("link_id"), py::arg("pose"),
DOC(mplib, PlanningWorldTpl, attachSphere))
Expand Down
8 changes: 4 additions & 4 deletions src/planning_world.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,22 +177,22 @@ void PlanningWorldTpl<S>::attachObject(const std::string &name,

template <typename S>
void PlanningWorldTpl<S>::attachObject(const std::string &name,
const CollisionGeometryPtr &p_geom,
const CollisionGeometryPtr &obj_geom,
const std::string &art_name, int link_id,
const Pose<S> &pose,
const std::vector<std::string> &touch_links) {
removeObject(name);
addObject(name, std::make_shared<CollisionObject>(p_geom));
addObject(name, std::make_shared<CollisionObject>(obj_geom));
attachObject(name, art_name, link_id, pose, touch_links);
}

template <typename S>
void PlanningWorldTpl<S>::attachObject(const std::string &name,
const CollisionGeometryPtr &p_geom,
const CollisionGeometryPtr &obj_geom,
const std::string &art_name, int link_id,
const Pose<S> &pose) {
removeObject(name);
addObject(name, std::make_shared<CollisionObject>(p_geom));
addObject(name, std::make_shared<CollisionObject>(obj_geom));
attachObject(name, art_name, link_id, pose);
}

Expand Down

0 comments on commit ab696c0

Please sign in to comment.