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

Example update and two convenience functions #84

Merged
merged 22 commits into from
Aug 27, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
22 commits
Select commit Hold shift + click to select a range
066bc61
allows for mutable p inside a mplib.Pose
Lexseal Apr 17, 2024
4802b69
get the simple demo working
Lexseal Apr 17, 2024
c9218ef
disable ground collision
Lexseal Apr 18, 2024
91631bc
added convenience function to attach objects
Lexseal Apr 18, 2024
3e84c4b
modified all examples as well as added documentation to planning world
Lexseal Apr 19, 2024
c433597
Remove attachCurrentlyTouchingObject method
KolinGuo Apr 19, 2024
693745a
Surround acm_/default_entries_ with backticks
KolinGuo Apr 19, 2024
ab696c0
Rename p_geom to obj_geom in PlanningWorld::attachObject
KolinGuo Apr 19, 2024
4ac8223
moved up panda so it's not touching the ground
Lexseal Apr 20, 2024
8148370
Override SapienPlanningWorld.attach/detach_object to accept SAPIEN ob…
KolinGuo Apr 20, 2024
52adf0d
remove commented out test code
Lexseal Apr 20, 2024
329fa4c
Merge branch 'example-update' of github.com:haosulab/MPlib into examp…
Lexseal Apr 20, 2024
fd53ea6
Override SapienPlanningWorld.attach_sphere/box/mesh to accept SAPIEN …
KolinGuo Apr 20, 2024
382f663
Override 3 more SapienPlanningWorld methods to accept SAPIEN objects
KolinGuo Apr 20, 2024
d8ee50e
output warning for initial colliding bodies during sapien conversion
Lexseal Apr 20, 2024
83bef5f
Merge branch 'example-update' of github.com:haosulab/MPlib into examp…
Lexseal Apr 20, 2024
159897e
Add no-index to all automethods
KolinGuo Apr 20, 2024
cd58e01
more sapien overloaded functions
Lexseal Apr 22, 2024
ab65bdb
warning color
Lexseal Apr 22, 2024
83a25f5
added tests and expanded the object types for set_allowed_collision
Lexseal Apr 22, 2024
8603aa9
install sapien for test
Lexseal Apr 22, 2024
b236441
disable sapien tests for now. requires swiftshader in the docker cont…
Lexseal Apr 23, 2024
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
6 changes: 3 additions & 3 deletions data/panda/panda_on_rail.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@
<link name="track_y">
<visual>
<geometry>
<box size="0.1 1 0.2"/>
<box size="0.1 1 0.1"/>
</geometry>
</visual>
</link>
<joint name="move_x" type="prismatic">
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 0.01"/>
<parent link="track_x"/>
<child link="track_y"/>
<axis xyz="1 0 0"/>
Expand All @@ -39,7 +39,7 @@
</collision>
</link>
<joint name="move_y" type="prismatic">
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 0.01"/>
<parent link="track_y"/>
<child link="panda_link0"/>
<axis xyz="0 1 0"/>
Expand Down
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
51 changes: 36 additions & 15 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,33 +284,33 @@ 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);

/**
Expand Down Expand Up @@ -349,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 @@ -358,6 +358,15 @@ 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.
*
* @param also_remove: whether to also remove objects from world
* @return: ``true`` if success, ``false`` if there are no attached objects
*/
bool detachAllObjects(bool also_remove = false);

/// @brief Prints global pose of all attached bodies
void printAttachedBodyPose() const;

Expand All @@ -375,6 +384,18 @@ class PlanningWorldTpl {
/// @brief Get the current allowed collision matrix
AllowedCollisionMatrixPtr getAllowedCollisionMatrix() const { return acm_; }

/**
* Set the allowed collision. For more comprehensive API, please get the
* ``AllowedCollisionMatrix`` object and use its methods.
*
* @param name1: name of the first object
* @param name2: name of the second object
*/
void setAllowedCollision(const std::string &name1, const std::string &name2,
bool allowed) {
acm_->setEntry(name1, name2, allowed);
}

/**
* Check if the current state is in collision (with the environment or self
* collision).
Expand Down
60 changes: 24 additions & 36 deletions mplib/examples/collision_avoidance.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
import numpy as np
import sapien.core as sapien

from mplib import Pose
from mplib.examples.demo_setup import DemoSetup
from mplib.sapien_utils import SapienPlanner, SapienPlanningWorld

Expand Down Expand Up @@ -36,56 +38,45 @@ def __init__(self):
# red box is the target we want to grab
builder = self.scene.create_actor_builder()
builder.add_box_collision(half_size=[0.02, 0.02, 0.06])
builder.add_box_visual(half_size=[0.02, 0.02, 0.06])
red_cube = builder.build(name="red_cube")
red_cube.set_pose(sapien.Pose([0.7, 0, 0.06]))
builder.add_box_visual(half_size=[0.02, 0.02, 0.06], material=[1, 0, 0])
self.red_cube = builder.build(name="red_cube")
self.red_cube.set_pose(sapien.Pose([0.7, 0, 0.06]))

# green box is the landing pad on which we want to place the red box
builder = self.scene.create_actor_builder()
builder.add_box_collision(half_size=[0.04, 0.04, 0.005])
builder.add_box_visual(half_size=[0.04, 0.04, 0.005])
builder.add_box_visual(half_size=[0.04, 0.04, 0.005], material=[0, 1, 0])
green_cube = builder.build(name="green_cube")
green_cube.set_pose(sapien.Pose([0.4, 0.3, 0.005]))

# blue box is the obstacle we want to avoid
builder = self.scene.create_actor_builder()
builder.add_box_collision(half_size=[0.05, 0.2, 0.1])
builder.add_box_visual(half_size=[0.05, 0.2, 0.1])
builder.add_box_visual(half_size=[0.05, 0.2, 0.1], material=[0, 0, 1])
blue_cube = builder.build(name="blue_cube")
blue_cube.set_pose(sapien.Pose([0.55, 0, 0.1]))

planning_world = SapienPlanningWorld(self.scene, [self.robot])
self.planner = SapienPlanner(planning_world, "panda_hand")
# disable collision between the base and the ground
self.planner.planning_world.get_allowed_collision_matrix().set_entry(
"panda_link0", "ground_1", True
)

def add_point_cloud(self):
"""We tell the planner about the obstacle through a point cloud"""
import trimesh

# add_point_cloud ankor
box = trimesh.creation.box([0.1, 0.4, 0.2])
points, _ = trimesh.sample.sample_surface(box, 1000)
points += [0.55, 0, 0.1]
self.planner.update_point_cloud(points, resolution=0.02)
# add_point_cloud ankor end

def demo(self, with_screw=True, use_point_cloud=True, use_attach=True):
def demo(self, with_screw=True, use_attach=True):
"""
We pick up the red box while avoiding the blue box and
place it back down on top of the green box.
"""
pickup_pose = [0.7, 0, 0.12, 0, 1, 0, 0]
delivery_pose = [0.4, 0.3, 0.13, 0, 1, 0, 0]

# tell the planner where the obstacle is
if use_point_cloud:
self.add_point_cloud()
pickup_pose = Pose([0.7, 0, 0.12], [0, 1, 0, 0])
delivery_pose = Pose([0.4, 0.3, 0.13], [0, 1, 0, 0])

# move to the pickup pose
pickup_pose[2] += 0.2
pickup_pose.p[2] += 0.2
# no need to check collision against attached object since nothing picked up yet
self.move_to_pose(pickup_pose, with_screw)
self.open_gripper()
pickup_pose[2] -= 0.12
pickup_pose.p[2] -= 0.12
# no attach since nothing picked up yet
self.move_to_pose(pickup_pose, with_screw)
self.close_gripper()
Expand All @@ -94,24 +85,21 @@ def demo(self, with_screw=True, use_point_cloud=True, use_attach=True):

# use_attach ankor
if use_attach:
self.planner.update_attached_box(
[0.04, 0.04, 0.12], [0, 0, 0.14, 1, 0, 0, 0]
)
idx = self.planner.user_link_names.index("panda_hand")
self.planner.planning_world.attach_object(self.red_cube, self.robot, idx)
# use_attach ankor end

# move to the delivery pose
pickup_pose[2] += 0.12
pickup_pose.p[2] += 0.12
self.move_to_pose(pickup_pose, with_screw)
delivery_pose[2] += 0.2
delivery_pose.p[2] += 0.2
self.move_to_pose(delivery_pose, with_screw)
delivery_pose[2] -= 0.12
delivery_pose.p[2] -= 0.1
self.move_to_pose(delivery_pose, with_screw)
self.open_gripper()
delivery_pose[2] += 0.12
delivery_pose.p[2] += 0.12
if use_attach:
ret = self.planner.detach_object(
f"robot_{self.planner.move_group_link_id}_box", also_remove=True
)
ret = self.planner.planning_world.detach_all_objects()
assert ret, "object is not attached"
self.move_to_pose(delivery_pose, with_screw)

Expand All @@ -126,4 +114,4 @@ def demo(self, with_screw=True, use_point_cloud=True, use_attach=True):
the delivery pose
"""
demo = PlanningDemo()
demo.demo(False, True, True)
demo.demo(False, True)
9 changes: 5 additions & 4 deletions mplib/examples/constrained_planning.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import numpy as np
import transforms3d

from mplib import Pose
from mplib.examples.demo_setup import DemoSetup


Expand Down Expand Up @@ -36,7 +37,7 @@ def get_eef_z(self):
"""Helper function for constraint"""
ee_idx = self.planner.link_name_2_idx[self.planner.move_group]
ee_pose = self.planner.robot.get_pinocchio_model().get_link_pose(ee_idx)
mat = transforms3d.quaternions.quat2mat(ee_pose[3:])
mat = transforms3d.quaternions.quat2mat(ee_pose.q)
return mat[:, 2]

def make_f(self):
Expand Down Expand Up @@ -94,9 +95,9 @@ def demo(self):
self.planner.robot.set_qpos(starting_qpos[:7])
# all these poses are constrain compatible (roughly 15 degrees w.r.t. -z axis)
poses = [
[-0.4, -0.3, 0.28, 0.0704682, -0.5356872, 0.8342834, 0.1097478],
[0.6, 0.1, 0.44, 0.0704682, -0.5356872, -0.8342834, -0.1097478],
[0, -0.3, 0.5, 0.1304237, -0.9914583, 0, 0],
Pose([-0.4, -0.3, 0.28], [0.0704682, -0.5356872, 0.8342834, 0.1097478]),
Pose([0.6, 0.1, 0.44], [0.0704682, -0.5356872, -0.8342834, -0.1097478]),
Pose([0, -0.3, 0.5], [0.1304237, -0.9914583, 0, 0]),
]

# add some point cloud to make the planning more challenging
Expand Down
25 changes: 13 additions & 12 deletions mplib/examples/demo.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
import sapien.core as sapien

from mplib import Pose
from mplib.examples.demo_setup import DemoSetup


Expand Down Expand Up @@ -36,19 +37,19 @@ def __init__(self):
# boxes ankor
builder = self.scene.create_actor_builder()
builder.add_box_collision(half_size=[0.02, 0.02, 0.06])
builder.add_box_visual(half_size=[0.02, 0.02, 0.06])
builder.add_box_visual(half_size=[0.02, 0.02, 0.06], material=[1, 0, 0])
red_cube = builder.build(name="red_cube")
red_cube.set_pose(sapien.Pose([0.4, 0.3, 0.06]))

builder = self.scene.create_actor_builder()
builder.add_box_collision(half_size=[0.02, 0.02, 0.04])
builder.add_box_visual(half_size=[0.02, 0.02, 0.04])
builder.add_box_visual(half_size=[0.02, 0.02, 0.04], material=[0, 1, 0])
green_cube = builder.build(name="green_cube")
green_cube.set_pose(sapien.Pose([0.2, -0.3, 0.04]))

builder = self.scene.create_actor_builder()
builder.add_box_collision(half_size=[0.02, 0.02, 0.07])
builder.add_box_visual(half_size=[0.02, 0.02, 0.07])
builder.add_box_visual(half_size=[0.02, 0.02, 0.07], material=[0, 0, 1])
blue_cube = builder.build(name="blue_cube")
blue_cube.set_pose(sapien.Pose([0.6, 0.1, 0.07]))
# boxes ankor end
Expand All @@ -61,28 +62,28 @@ def demo(self):
"""
# target poses ankor
poses = [
[0.4, 0.3, 0.12, 0, 1, 0, 0],
[0.2, -0.3, 0.08, 0, 1, 0, 0],
[0.6, 0.1, 0.14, 0, 1, 0, 0],
Pose([0.4, 0.3, 0.12], [0, 1, 0, 0]),
Pose([0.2, -0.3, 0.08], [0, 1, 0, 0]),
Pose([0.6, 0.1, 0.14], [0, 1, 0, 0]),
]
# target poses ankor end
# execute motion ankor
for i in range(3):
pose = poses[i]
pose[2] += 0.2
pose.p[2] += 0.2
self.move_to_pose(pose)
self.open_gripper()
pose[2] -= 0.12
pose.p[2] -= 0.12
self.move_to_pose(pose)
self.close_gripper()
pose[2] += 0.12
pose.p[2] += 0.12
self.move_to_pose(pose)
pose[0] += 0.1
pose.p[0] += 0.1
self.move_to_pose(pose)
pose[2] -= 0.12
pose.p[2] -= 0.12
self.move_to_pose(pose)
self.open_gripper()
pose[2] += 0.12
pose.p[2] += 0.12
self.move_to_pose(pose)
# execute motion ankor end

Expand Down
Loading