diff --git a/cfg/scenes/scene1.yaml b/cfg/scenes/mustard.yaml similarity index 100% rename from cfg/scenes/scene1.yaml rename to cfg/scenes/mustard.yaml diff --git a/scripts/reset.py b/scripts/reset.py index 6907daa..7c17454 100644 --- a/scripts/reset.py +++ b/scripts/reset.py @@ -8,7 +8,5 @@ seed = rospy.ServiceProxy("seed", Seed) reset = rospy.ServiceProxy("reset", Reset) seed(SeedRequest(1)) - -while True: - reset(ResetRequest()) - rospy.sleep(1.0) +reset(ResetRequest()) +rospy.sleep(1.0) diff --git a/src/active_grasp/simulation.py b/src/active_grasp/simulation.py index bfa57dc..2fd6a5e 100644 --- a/src/active_grasp/simulation.py +++ b/src/active_grasp/simulation.py @@ -1,7 +1,6 @@ from pathlib import Path import pybullet as p import pybullet_data -import yaml import rospkg from active_grasp.bbox import AABBox @@ -50,7 +49,7 @@ class Simulation: self.camera = BtCamera(320, 240, 0.96, 0.01, 1.0, self.arm.uid, 11) def reset(self): - self.set_arm_configuration([0.0, -0.79, 0.0, -2.356, 0.0, 1.57, 0.79]) + self.set_arm_configuration([0.0, -1.39, 0.0, -2.36, 0.0, 1.57, 0.79]) self.scene.clear() q = self.scene.generate(self.rng) self.set_arm_configuration(q)