nbv_sim/src/active_grasp/simulation.py

202 lines
6.7 KiB
Python
Raw Normal View History

2021-05-26 14:46:12 +02:00
from pathlib import Path
2021-04-26 20:10:52 +02:00
import pybullet as p
2021-07-22 11:05:30 +02:00
import pybullet_data
2021-09-08 16:50:53 +02:00
import yaml
2021-05-26 14:46:12 +02:00
import rospkg
2021-04-26 20:10:52 +02:00
2021-07-22 11:05:30 +02:00
from active_grasp.bbox import AABBox
from robot_helpers.bullet import *
2021-09-12 00:21:58 +02:00
from robot_helpers.model import KDLModel
2021-09-07 22:29:42 +02:00
from robot_helpers.spatial import Rotation
rospack = rospkg.RosPack()
2021-04-26 20:10:52 +02:00
2021-09-14 11:58:33 +02:00
active_grasp_urdfs_dir = Path(rospack.get_path("active_grasp")) / "assets" / "urdfs"
urdf_zoo_dir = Path(rospack.get_path("urdf_zoo")) / "models"
2021-04-26 20:10:52 +02:00
2021-07-22 11:05:30 +02:00
class Simulation:
2021-09-07 22:29:42 +02:00
"""Robot is placed s.t. world and base frames are the same"""
def __init__(self, gui, scene_id):
2021-07-22 11:05:30 +02:00
self.configure_physics_engine(gui, 60, 4)
2021-07-09 15:53:34 +02:00
self.configure_visualizer()
2021-07-06 14:00:04 +02:00
self.load_robot()
2021-09-07 22:29:42 +02:00
self.scene = get_scene(scene_id)
2021-07-22 11:05:30 +02:00
def configure_physics_engine(self, gui, rate, sub_step_count):
self.rate = rate
self.dt = 1.0 / self.rate
p.connect(p.GUI if gui else p.DIRECT)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.setPhysicsEngineParameter(fixedTimeStep=self.dt, numSubSteps=sub_step_count)
p.setGravity(0.0, 0.0, -9.81)
2021-05-26 14:46:12 +02:00
2021-07-09 15:53:34 +02:00
def configure_visualizer(self):
# p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0)
2021-09-07 22:29:42 +02:00
p.resetDebugVisualizerCamera(1.2, 30, -30, [0.4, 0.0, 0.2])
2021-05-26 14:46:12 +02:00
2021-07-06 14:00:04 +02:00
def load_robot(self):
2021-09-14 11:58:33 +02:00
panda_urdf_path = active_grasp_urdfs_dir / "franka/panda_arm_hand.urdf"
2021-09-12 00:21:58 +02:00
self.arm = BtPandaArm(panda_urdf_path)
2021-04-27 11:45:57 +02:00
self.gripper = BtPandaGripper(self.arm)
2021-09-12 00:21:58 +02:00
self.model = KDLModel.from_urdf_file(
panda_urdf_path, self.arm.base_frame, self.arm.ee_frame
)
2021-09-10 23:29:15 +02:00
self.camera = BtCamera(320, 240, 0.96, 0.01, 1.0, self.arm.uid, 11)
2021-04-26 20:10:52 +02:00
2021-07-22 11:05:30 +02:00
def seed(self, seed):
self.rng = np.random.default_rng(seed)
2021-04-26 20:10:52 +02:00
def reset(self):
self.set_arm_configuration([0.0, -0.79, 0.0, -2.356, 0.0, 1.57, 0.79])
self.scene.reset(rng=self.rng)
q = self.scene.sample_initial_configuration(self.rng)
self.set_arm_configuration(q)
2021-07-07 10:16:12 +02:00
uid = self.select_target()
2021-09-07 22:29:42 +02:00
bbox = self.get_target_bbox(uid)
return bbox
2021-07-22 11:05:30 +02:00
def set_arm_configuration(self, q):
2021-04-26 20:10:52 +02:00
for i, q_i in enumerate(q):
p.resetJointState(self.arm.uid, i, q_i, 0)
2021-07-06 14:00:04 +02:00
p.resetJointState(self.arm.uid, 9, 0.04, 0)
p.resetJointState(self.arm.uid, 10, 0.04, 0)
2021-09-07 22:29:42 +02:00
def select_target(self):
_, _, mask = self.camera.get_image()
uids, counts = np.unique(mask, return_counts=True)
mask = np.isin(uids, self.scene.object_uids) # remove ids of the floor, etc
uids, counts = uids[mask], counts[mask]
target_uid = uids[np.argmin(counts)]
p.changeVisualShape(target_uid, -1, rgbaColor=[1, 0, 0, 1])
return target_uid
def get_target_bbox(self, uid):
aabb_min, aabb_max = p.getAABB(uid)
return AABBox(aabb_min, aabb_max)
def step(self):
p.stepSimulation()
class Scene:
def __init__(self):
2021-09-14 11:58:33 +02:00
self.support_urdf = urdf_zoo_dir / "plane" / "model.urdf"
self.ycb_urdfs_dir = urdf_zoo_dir / "ycb"
2021-09-07 22:29:42 +02:00
self.support_uid = -1
self.object_uids = []
2021-09-08 16:50:53 +02:00
def load_support(self, pos):
2021-09-13 18:29:41 +02:00
self.support_uid = p.loadURDF(str(self.support_urdf), pos, globalScaling=0.3)
2021-09-07 22:29:42 +02:00
def remove_support(self):
2021-09-08 16:50:53 +02:00
p.removeBody(self.support_uid)
2021-09-07 22:29:42 +02:00
2021-07-06 14:00:04 +02:00
def load_object(self, urdf, ori, pos, scale=1.0):
uid = p.loadURDF(str(urdf), pos, ori.as_quat(), globalScaling=scale)
self.object_uids.append(uid)
return uid
def remove_object(self, uid):
p.removeBody(uid)
self.object_uids.remove(uid)
def remove_all_objects(self):
for uid in list(self.object_uids):
self.remove_object(uid)
2021-09-07 22:29:42 +02:00
def reset(self, rng):
self.remove_support()
self.remove_all_objects()
self.load(rng)
def load(self, rng):
raise NotImplementedError
2021-09-08 16:50:53 +02:00
def get_ycb_urdf_path(self, model_name):
return self.ycb_urdfs_dir / model_name / "model.urdf"
2021-09-07 22:29:42 +02:00
def find_urdfs(root):
# Scans a dir for URDF assets
return [str(f) for f in root.iterdir() if f.suffix == ".urdf"]
class RandomScene(Scene):
def __init__(self):
super().__init__()
2021-09-14 11:58:33 +02:00
self.center = np.r_[0.5, 0.0, 0.2]
2021-09-07 22:29:42 +02:00
self.length = 0.3
self.origin = self.center - np.r_[0.5 * self.length, 0.5 * self.length, 0.0]
2021-09-14 11:58:33 +02:00
self.object_urdfs = find_urdfs(active_grasp_urdfs_dir / "packed")
2021-09-07 22:29:42 +02:00
def load(self, rng, attempts=10):
2021-09-08 16:50:53 +02:00
self.load_support(self.center)
2021-09-14 11:58:33 +02:00
urdfs = rng.choice(self.object_urdfs, 4)
scale = 1.0
2021-07-06 14:00:04 +02:00
for urdf in urdfs:
2021-09-07 22:29:42 +02:00
uid = self.load_object(urdf, Rotation.identity(), np.zeros(3), scale)
2021-07-06 14:00:04 +02:00
lower, upper = p.getAABB(uid)
z_offset = 0.5 * (upper[2] - lower[2]) + 0.002
state_id = p.saveState()
for _ in range(attempts):
2021-09-07 22:29:42 +02:00
# Try to place and check for collisions
ori = Rotation.from_rotvec([0.0, 0.0, rng.uniform(0, 2 * np.pi)])
pos = np.r_[rng.uniform(0.2, 0.8, 2) * self.length, z_offset]
p.resetBasePositionAndOrientation(uid, self.origin + pos, ori.as_quat())
p.stepSimulation()
2021-07-06 14:00:04 +02:00
if not p.getContactPoints(uid):
break
else:
p.restoreState(stateId=state_id)
else:
# No placement found, remove the object
self.remove_object(uid)
def sample_initial_configuration(self, rng):
2021-09-14 11:58:33 +02:00
q = [0.0, -1.39, 0.0, -2.36, 0.0, 1.57, 0.79]
q += rng.uniform(-0.08, 0.08, 7)
return q
2021-07-07 10:16:12 +02:00
2021-09-08 16:50:53 +02:00
class CustomScene(Scene):
def __init__(self, config_name):
super().__init__()
2021-09-09 21:19:30 +02:00
self.config_path = (
Path(rospack.get_path("active_grasp")) / "cfg" / "scenes" / config_name
)
def load_config(self):
with self.config_path.open("r") as f:
2021-10-08 17:19:36 +02:00
self.scene = yaml.load(f, Loader=yaml.FullLoader)
2021-09-08 16:50:53 +02:00
self.center = np.asarray(self.scene["center"])
self.length = 0.3
self.origin = self.center - np.r_[0.5 * self.length, 0.5 * self.length, 0.0]
def load(self, rng):
2021-09-09 21:19:30 +02:00
self.load_config()
2021-09-08 16:50:53 +02:00
self.load_support(self.center)
for object in self.scene["objects"]:
self.load_object(
self.get_ycb_urdf_path(object["object_id"]),
2021-09-09 21:19:30 +02:00
Rotation.from_euler("xyz", object["rpy"], degrees=True),
2021-09-08 16:50:53 +02:00
self.center + np.asarray(object["xyz"]),
2021-09-10 23:29:15 +02:00
object.get("scale", 1),
2021-09-08 16:50:53 +02:00
)
2021-09-10 23:29:15 +02:00
for _ in range(60):
p.stepSimulation()
2021-09-08 16:50:53 +02:00
def sample_initial_configuration(self, rng):
2021-09-10 23:29:15 +02:00
return self.scene["q"]
2021-09-07 22:29:42 +02:00
def get_scene(scene_id):
2021-09-08 16:50:53 +02:00
if scene_id == "random":
return RandomScene()
elif scene_id.endswith(".yaml"):
return CustomScene(scene_id)
2021-09-07 22:29:42 +02:00
else:
raise ValueError("Unknown scene {}.".format(scene_id))