Minor
This commit is contained in:
parent
29b3ba7759
commit
33d123e3ee
@ -2,7 +2,7 @@ bt_sim:
|
|||||||
gui: False
|
gui: False
|
||||||
cam_noise: False
|
cam_noise: False
|
||||||
gripper_force: 10
|
gripper_force: 10
|
||||||
scene: scene1.yaml
|
scene: random
|
||||||
|
|
||||||
grasp_controller:
|
grasp_controller:
|
||||||
base_frame_id: panda_link0
|
base_frame_id: panda_link0
|
||||||
|
@ -2,10 +2,13 @@ import rospy
|
|||||||
|
|
||||||
from active_grasp.srv import *
|
from active_grasp.srv import *
|
||||||
|
|
||||||
rospy.init_node("test")
|
rospy.init_node("reset")
|
||||||
|
|
||||||
seed = rospy.ServiceProxy("seed", Seed)
|
seed = rospy.ServiceProxy("seed", Seed)
|
||||||
reset = rospy.ServiceProxy("reset", Reset)
|
reset = rospy.ServiceProxy("reset", Reset)
|
||||||
|
|
||||||
# seed(SeedRequest(1))
|
seed(SeedRequest(1))
|
||||||
|
|
||||||
|
while True:
|
||||||
reset(ResetRequest())
|
reset(ResetRequest())
|
||||||
|
rospy.sleep(1.0)
|
||||||
|
@ -153,18 +153,18 @@ class RandomScene(Scene):
|
|||||||
self.origin = self.center - np.r_[0.5 * self.length, 0.5 * self.length, 0.0]
|
self.origin = self.center - np.r_[0.5 * self.length, 0.5 * self.length, 0.0]
|
||||||
self.object_urdfs = find_urdfs(assets_dir / "test")
|
self.object_urdfs = find_urdfs(assets_dir / "test")
|
||||||
|
|
||||||
def generate(self, rng, attempts=10):
|
def generate(self, rng, object_count=4, attempts=10):
|
||||||
self.add_support(self.center)
|
self.add_support(self.center)
|
||||||
urdfs = rng.choice(self.object_urdfs, 4)
|
urdfs = rng.choice(self.object_urdfs, object_count)
|
||||||
scale = 1.0
|
|
||||||
for urdf in urdfs:
|
for urdf in urdfs:
|
||||||
|
scale = rng.uniform(0.8, 1.0)
|
||||||
uid = self.add_object(urdf, Rotation.identity(), np.zeros(3), scale)
|
uid = self.add_object(urdf, Rotation.identity(), np.zeros(3), scale)
|
||||||
lower, upper = p.getAABB(uid)
|
lower, upper = p.getAABB(uid)
|
||||||
z_offset = 0.5 * (upper[2] - lower[2]) + 0.002
|
z_offset = 0.5 * (upper[2] - lower[2]) + 0.002
|
||||||
state_id = p.saveState()
|
state_id = p.saveState()
|
||||||
for _ in range(attempts):
|
for _ in range(attempts):
|
||||||
# Try to place and check for collisions
|
# Try to place and check for collisions
|
||||||
ori = Rotation.from_rotvec([0.0, 0.0, rng.uniform(0, 2 * np.pi)])
|
ori = Rotation.from_euler("z", rng.uniform(0, 2 * np.pi))
|
||||||
pos = np.r_[rng.uniform(0.2, 0.8, 2) * self.length, z_offset]
|
pos = np.r_[rng.uniform(0.2, 0.8, 2) * self.length, z_offset]
|
||||||
p.resetBasePositionAndOrientation(uid, self.origin + pos, ori.as_quat())
|
p.resetBasePositionAndOrientation(uid, self.origin + pos, ori.as_quat())
|
||||||
p.stepSimulation()
|
p.stepSimulation()
|
||||||
|
Loading…
x
Reference in New Issue
Block a user