def fn(self, edge, object_name, object_pose): oracle = self.oracle preprocess_edge(oracle, edge) object_aabb = oracle.get_aabb(object_name, trans_from_pose(object_pose.value)) object_aabb_min, object_aabb_max = aabb_min(object_aabb), aabb_max( object_aabb) configs = [ q for q in edge.configs() if fast_aabb_overlap(object_aabb_min, object_aabb_max, q.aabbs) ] if len(configs) == 0: return False #distance = oracle.get_radius2('pr2') + oracle.get_radius2(object_name) #z = get_point(oracle.robot)[-1] #configs = [q for q in edge.configs() if length2(np.array([q.value[-3], q.value[-2], z]) - point_from_pose(object_pose.value)) <= distance] #if len(configs) == 0: return False # TODO - oracle.robot.SetActiveDOFValues(q.value) is the bottleneck: check each object at the same time with oracle.body_saver(object_name): oracle.set_pose(object_name, object_pose) with oracle.robot_saver(): CSpace.robot_arm_and_base( oracle.robot.GetActiveManipulator()).set_active() with collision_saver( oracle.env, openravepy_int.CollisionOptions.ActiveDOFs ): # TODO - does this really do what I think? for q in configs: # TODO - do this with other other collision functions q.saver.Restore() if robot_collision(oracle, object_name): return True return False
def compile_problem(oracle): problem = oracle.problem CSpace.robot_base(oracle.robot).set_active() initial_config = Config( base_values_from_full_config(oracle.initial_config.value)) initial_atoms = [ AtConfig(Conf(initial_config)), ] print 'Initial', initial_config.value goal_literals = [AtConfig(Conf(problem.goal_config)) ] if problem.goal_config is not None else [] print 'Goal', problem.goal_config.value actions = [ Move(oracle), ] axioms = [ #InRegionAxiom(), ] cond_streams = [ CollisionFreeTest(oracle), ConfStream(oracle), ] objects = [] return STRIPStreamProblem(initial_atoms, goal_literals, actions + axioms, cond_streams, objects)
def fn(self, edge, object_name, object_pose): oracle = self.oracle preprocess_edge(oracle, edge) object_aabb = oracle.get_aabb(object_name, trans_from_pose(object_pose.value)) object_aabb_min, object_aabb_max = aabb_min(object_aabb), aabb_max(object_aabb) configs = [q for q in edge.configs() if fast_aabb_overlap(object_aabb_min, object_aabb_max, q.aabbs)] if len(configs) == 0: return False #distance = oracle.get_radius2('pr2') + oracle.get_radius2(object_name) #z = get_point(oracle.robot)[-1] #configs = [q for q in edge.configs() if length2(np.array([q.value[-3], q.value[-2], z]) - point_from_pose(object_pose.value)) <= distance] #if len(configs) == 0: return False # TODO - oracle.robot.SetActiveDOFValues(q.value) is the bottleneck: check each object at the same time with oracle.body_saver(object_name): oracle.set_pose(object_name, object_pose) with oracle.robot_saver(): CSpace.robot_arm_and_base(oracle.robot.GetActiveManipulator()).set_active() with collision_saver(oracle.env, openravepy_int.CollisionOptions.ActiveDOFs): # TODO - does this really do what I think? for q in configs: # TODO - do this with other other collision functions q.saver.Restore() if robot_collision(oracle, object_name): return True return False
def preprocess_edge(oracle, edge): if not hasattr(edge, 'preprocessed'): edge.preprocessed = True with oracle.robot_saver(): CSpace.robot_arm_and_base(oracle.robot.GetActiveManipulator()).set_active() for q in edge.configs(): if not hasattr(q, 'saver'): oracle.robot.SetActiveDOFValues(q.value) q.saver = oracle.robot_saver() q.manip_trans = get_manip_trans(oracle) q.aabbs = [(aabb_min(aabb), aabb_max(aabb)) for aabb in [oracle.compute_part_aabb(part) for part in USE_ROBOT_PARTS]]
def preprocess_edge(oracle, edge): if not hasattr(edge, 'preprocessed'): edge.preprocessed = True with oracle.robot_saver(): CSpace.robot_arm_and_base( oracle.robot.GetActiveManipulator()).set_active() for q in edge.configs(): if not hasattr(q, 'saver'): oracle.robot.SetActiveDOFValues(q.value) q.saver = oracle.robot_saver() q.manip_trans = get_manip_trans(oracle) q.aabbs = [(aabb_min(aabb), aabb_max(aabb)) for aabb in [ oracle.compute_part_aabb(part) for part in USE_ROBOT_PARTS ]]
def load_grasp_database(robot, filename): grasps = [] for grasp_tform, gripper_config, (trajectory, indices), approach_vector in read_pickle(filename): grasps.append(Grasp(np.array(grasp_tform), np.array(gripper_config), TrajTrajectory(CSpace(robot, indices=np.array(indices)), new_traj().deserialize(trajectory)), approach_vector)) if DEBUG: print 'Loaded', filename return grasps
def initialize_openrave(env, arm, min_delta=.01, collision_checker='ode'): env.StopSimulation() for sensor in env.GetSensors(): sensor.Configure(Sensor.ConfigureCommand.PowerOff) sensor.Configure(Sensor.ConfigureCommand.RenderDataOff) sensor.Configure(Sensor.ConfigureCommand.RenderGeometryOff) env.Remove(sensor) env.SetCollisionChecker(RaveCreateCollisionChecker(env, collision_checker)) env.GetCollisionChecker().SetCollisionOptions(0) robot = env.GetRobots()[0] cd_model = databases.convexdecomposition.ConvexDecompositionModel(robot) if not cd_model.load(): cd_model.autogenerate() l_model = databases.linkstatistics.LinkStatisticsModel(robot) if not l_model.load(): l_model.autogenerate() l_model.setRobotWeights() l_model.setRobotResolutions(xyzdelta=min_delta) # xyzdelta is the minimum Cartesian distance of an object or_arm = 'leftarm' if arm == 'l' else 'rightarm' robot.SetActiveManipulator(or_arm) # NOTE - Need this or the manipulator computations are off #extrema = aabb_extrema(aabb_union([aabb_from_body(body) for body in env.GetBodies()])).T #robot.SetAffineTranslationLimits(*extrema) ikmodel = databases.inversekinematics.InverseKinematicsModel(robot=robot, iktype=IkParameterization.Type.Transform6D, forceikfast=True, freeindices=None, freejoints=None, manip=None) if not ikmodel.load(): ikmodel.autogenerate() cspace = CSpace.robot_arm(robot.GetActiveManipulator()) cspace.set_active()
def process_scan_room(robot): # TODO: could do this whole thing symbolically using point head path = get_scan_path(robot, math.pi / 6) if path is None: raise RuntimeError() cspace = CSpace.robot_manipulator(robot, 'head') h_traj = PathTrajectory(cspace, path) h_traj.traj() # Precompute the traj return [h_traj]
def sample_trajectory(robot, q1, q2, name, **kwargs): cspace = CSpace.robot_manipulator(robot, name) cspace.name = name with robot: cspace.set_active() base_path = mp_birrt(robot, q1, q2, **kwargs) if base_path is None: return None return PathTrajectory(cspace, base_path)
def sample_motion(q1, q2): if not DO_BASE_MOTION: yield [None] #with oracle.robot: # NOTE - this causes an segfault when freeing the memory oracle.set_robot_config(q1) goal = base_values_from_full_config(q2.value) traj = motion_plan(oracle.env, CSpace.robot_base(oracle.robot), goal) if traj is not None: traj.obj = None yield [traj]
def sample_motion(q1, q2): if not DO_BASE_MOTION: yield [None] with oracle.robot: oracle.set_robot_config(q1) goal = base_values_from_full_config(q2.value) traj = motion_plan(oracle.env, CSpace.robot_base(oracle.robot), goal) if traj is not None: traj.obj = None yield [traj]
def collision_ignorant_grasp(oracle, geom_hash, grasp_tform, approach_vector, manip_name=None): # TODO - try to make a valid grasp if possible with oracle.state_saver(): if manip_name is not None: oracle.robot.SetActiveManipulator(manip_name) oracle.set_active_state(active_obstacles=False, active_objects=set()) open_gripper(oracle) oracle.robot.SetDOFValues(oracle.default_left_arm_config, oracle.robot.GetActiveManipulator().GetArmIndices()) gripper_config, gripper_traj = oracle.task_manip.CloseFingers(offset=None, movingdir=None, execute=False, outputtraj=False, outputfinal=True, coarsestep=None, translationstepmult=None, finestep=None, outputtrajobj=True) return Grasp(grasp_tform, gripper_config, TrajTrajectory(CSpace(oracle.robot, indices=oracle.robot.GetActiveManipulator().GetGripperIndices()), gripper_traj), approach_vector)
def collision_free_grasp(oracle, geom_hash, grasp_tform, approach_vector, manip_name=None): body_name = oracle.get_body_name(geom_hash) with oracle.state_saver(): if manip_name is not None: oracle.robot.SetActiveManipulator(manip_name) oracle.set_active_state(active_obstacles=False, active_objects=set([body_name])) open_gripper(oracle) oracle.robot.SetDOFValues(oracle.default_left_arm_config, oracle.robot.GetActiveManipulator().GetArmIndices()) set_trans(oracle.bodies[body_name], object_trans_from_manip_trans(get_manip_trans(oracle), grasp_tform)) if not robot_collision(oracle, body_name): gripper_config, gripper_traj = oracle.task_manip.CloseFingers(offset=None, movingdir=None, execute=False, outputtraj=False, outputfinal=True, coarsestep=None, translationstepmult=None, finestep=None, outputtrajobj=True) return Grasp(grasp_tform, gripper_config, TrajTrajectory(CSpace(oracle.robot, indices=oracle.robot.GetActiveManipulator().GetGripperIndices()), gripper_traj), approach_vector) return None
def sample_base_trajectory(robot, q1, q2, **kwargs): # TODO: ActiveDOFs doesn't work here for FCL? env = robot.GetEnv() cspace = CSpace.robot_manipulator(robot, 'base') cspace.name = 'base' with robot: cspace.set_active() collision_fn = get_collision_fn(env, robot, self_collisions=False, limits=True) base_path = birrt(q1, q2, get_distance_fn(robot), get_sample_fn(env, robot), get_extend_fn(robot), collision_fn, **kwargs) if base_path is None: return None return PathTrajectory(cspace, base_path)
def feasible_pick_place(env, robot, obj, grasps, approach_config, do_motion_planning): base_manip = interfaces.BaseManipulation(robot, plannername=None, maxvelmult=None) pose = Pose(get_pose(obj)) for grasp in grasps: manip_trans, approach_vector = manip_from_pose_grasp(pose, grasp) set_config(robot, approach_config, robot.GetActiveManipulator().GetArmIndices()) if env.CheckCollision(robot) or robot.CheckSelfCollision(): continue grasp_config = inverse_kinematics_helper( env, robot, manip_trans) # NOTE - maybe need to find all IK solutions #grasp_config = solve_inverse_kinematics_exhaustive(env, robot, manip_trans) if grasp_config is None: continue set_config(robot, grasp_config, get_active_arm_indices(robot)) #approach_config = get_full_config(robot) traj, arm_traj = None, None if do_motion_planning: #traj = vector_traj_helper(env, robot, approach_vector) traj = workspace_traj_helper(base_manip, approach_vector) if traj is None: continue set_config(robot, traj.end(), get_active_arm_indices(robot)) #vector_config = oracle.get_robot_config() arm_traj = motion_plan(env, CSpace.robot_arm(get_manipulator(robot)), approach_config, self_collisions=True) if arm_traj is None: continue return grasp_config, traj, arm_traj return None
def open_gripper_trajectory(arm): cspace = CSpace.robot_gripper(arm) cspace.name = '{}_gripper'.format(arm.GetName()[0]) return PathTrajectory(cspace, [get_close_conf(arm), get_open_conf(arm)])
def solve_tamp(env): viewer = env.GetViewer() is not None problem = PROBLEM(env) robot = env.GetRobots()[0] set_base_conf(robot, (-.75, .2, -math.pi / 2)) initialize_openrave(env, ARM, min_delta=.01) manipulator = robot.GetActiveManipulator() cspace = CSpace.robot_arm(manipulator) base_manip = interfaces.BaseManipulation(robot, plannername=None, maxvelmult=None) bodies = {obj: env.GetKinBody(obj) for obj in problem.object_names} all_bodies = bodies.values() assert len({body.GetKinematicsGeometryHash() for body in all_bodies }) == 1 # NOTE - assuming all objects has the same geometry body1 = all_bodies[-1] # Generic object 1 body2 = all_bodies[-2] if len(bodies) >= 2 else body1 # Generic object 2 grasps = get_grasps(env, robot, body1, USE_GRASP_APPROACH, USE_GRASP_TYPE)[:MAX_GRASPS] poses = problem.known_poses if problem.known_poses else [] open_gripper(manipulator) initial_conf = Conf( robot.GetConfigurationValues()[manipulator.GetArmIndices()]) #################### cond_streams = [ # Pick/place trajectory EasyListGenStream(inputs=[P, G], outputs=[Q, T], conditions=[], effects=[GraspMotion(P, G, Q, T)], generator=sample_grasp_traj_fn( env, robot, manipulator, body1, all_bodies)), # Move trajectory EasyListGenStream(inputs=[Q, Q2], outputs=[T], conditions=[], effects=[FreeMotion(Q, Q2, T)], generator=sample_free_motion_fn( manipulator, base_manip, cspace, all_bodies), order=1, max_level=0), EasyListGenStream(inputs=[Q, Q2, G], outputs=[T], conditions=[], effects=[HoldingMotion(Q, Q2, G, T)], generator=sample_holding_motion_fn( robot, manipulator, base_manip, cspace, body1, all_bodies), order=1, max_level=0), # Collisions EasyTestStream(inputs=[P, P2], conditions=[], effects=[CFreePose(P, P2)], test=cfree_pose_fn(env, body1, body2), eager=True), EasyTestStream(inputs=[T, P], conditions=[], effects=[CFreeTraj(T, P)], test=cfree_traj_fn(env, robot, manipulator, body1, body2, all_bodies)), ] #################### constants = map(GRASP, grasps) + map(POSE, poses) initial_atoms = [ ConfEq(initial_conf), HandEmpty(), ] + [PoseEq(obj, pose) for obj, pose in problem.initial_poses.iteritems()] goal_formula = And( ConfEq(initial_conf), *(PoseEq(obj, pose) for obj, pose in problem.goal_poses.iteritems())) stream_problem = STRIPStreamProblem(initial_atoms, goal_formula, actions + axioms, cond_streams, constants) if viewer: raw_input('Start?') search_fn = get_fast_downward('eager', max_time=10, verbose=False) solve = lambda: incremental_planner( stream_problem, search=search_fn, frequency=1, waves=True, debug=False) #solve = lambda: simple_focused(stream_problem, search=search_fn, max_level=INF, shared=False, debug=False, verbose=False, max_time=15) env.Lock() plan, universe = solve() env.Unlock() print SEPARATOR plan = convert_plan(plan) if plan is not None: print 'Success' for i, (action, args) in enumerate(plan): print i + 1, action, args else: print 'Failure' #################### if viewer and plan is not None: print SEPARATOR visualize_solution(env, problem, initial_conf, robot, manipulator, bodies, plan) raw_input('Finish?')
def solve_tamp(env): viewer = env.GetViewer() is not None problem = PROBLEM(env) robot = env.GetRobots()[0] set_base_values(robot, (-.75, .2, -math.pi/2)) initialize_openrave(env, ARM) manipulator = robot.GetActiveManipulator() cspace = CSpace.robot_arm(manipulator) base_manip = interfaces.BaseManipulation(robot, plannername=None, maxvelmult=None) bodies = {obj: env.GetKinBody(obj) for obj in problem.object_names} geom_hashes = {body.GetKinematicsGeometryHash() for body in bodies.values()} assert len(geom_hashes) == 1 # NOTE - assuming all objects has the same geometry all_bodies = bodies.values() body1 = all_bodies[-1] body2 = all_bodies[-2] if len(bodies) >= 2 else body1 grasps = get_grasps(env, robot, body1, USE_GRASP_APPROACH, USE_GRASP_TYPE)[:1] poses = problem.known_poses if problem.known_poses else [] open_gripper2(manipulator) initial_manip = get_arm_conf(manipulator, Config(get_full_config(robot))) def enable_all(enable): for body in all_bodies: body.Enable(enable) #################### def cfree_pose_pose(pose1, pose2): body1.Enable(True) set_pose(body1, pose1.value) body2.Enable(True) set_pose(body2, pose2.value) return not env.CheckCollision(body1, body2) def cfree_gtraj_pose(gt, p): return cfree_mtraj_pose(gt, p) and cfree_mtraj_grasp_pose(gt, gt.grasp, p) #################### def cfree_mtraj_grasp(mt, g): enable_all(False) body1.Enable(True) for conf in mt.path(): set_manipulator_values(manipulator, conf) # NOTE - can also grab set_pose(body1, object_trans_from_manip_trans(get_trans(manipulator), g.grasp_trans)) if env.CheckCollision(body1): print 'cfree_mtraj_grasp' return False return True def cfree_mtraj_pose(mt, p): enable_all(False) body2.Enable(True) set_pose(body2, p.value) for conf in mt.path(): set_manipulator_values(manipulator, conf) if env.CheckCollision(robot, body2): print 'cfree_mtraj_pose' return False return True def cfree_mtraj_grasp_pose(mt, g, p): enable_all(False) body1.Enable(True) body2.Enable(True) set_pose(body2, p.value) for conf in mt.path(): set_manipulator_values(manipulator, conf) set_pose(body1, object_trans_from_manip_trans(get_trans(manipulator), g.grasp_trans)) if env.CheckCollision(body1, body2): print 'cfree_mtraj_grasp_pose' return False return True #################### def sample_grasp_traj(pose, grasp): enable_all(False) body1.Enable(True) set_pose(body1, pose.value) manip_trans, approach_vector = manip_from_pose_grasp(pose, grasp) grasp_config = inverse_kinematics_helper(env, robot, manip_trans) if grasp_config is None: return set_manipulator_values(manipulator, grasp_config) robot.Grab(body1) grasp_traj = workspace_traj_helper(base_manip, approach_vector) robot.Release(body1) if grasp_traj is None: return grasp_traj.grasp = grasp yield [(Config(grasp_traj.end()), grasp_traj)] def sample_manip_motion(mq1, mq2): enable_all(False) set_manipulator_values(manipulator, mq1.value) mt = motion_plan(env, cspace, mq2.value, self_collisions=True) if not mt: return yield [(mt,)] #################### cond_streams = [ # Pick/place trajectory EasyListGenStream(inputs=[P, G], outputs=[MQ, GT], conditions=[], effects=[GraspMotion(P, G, MQ, GT)], generator=sample_grasp_traj), # Move trajectory EasyListGenStream(inputs=[MQ, MQ2], outputs=[MT], conditions=[], effects=[ManipMotion(MQ, MQ2, MT)], generator=sample_manip_motion, order=1, max_level=0), # Pick/place collisions EasyTestStream(inputs=[P, P2], conditions=[], effects=[CFreePosePose(P, P2)], test=cfree_pose_pose, eager=True), EasyTestStream(inputs=[GT, P], conditions=[], effects=[CFreeGTrajPose(GT, P)], test=cfree_gtraj_pose), # Move collisions EasyTestStream(inputs=[MT, P], conditions=[], effects=[CFreeMTrajPose(MT, P)], test=cfree_mtraj_pose), EasyTestStream(inputs=[MT, G], conditions=[], effects=[CFreeMTrajGrasp(MT, G)], test=cfree_mtraj_grasp), EasyTestStream(inputs=[MT, G, P], conditions=[], effects=[CFreeMTrajGraspPose(MT, G, P)], test=cfree_mtraj_grasp_pose), ] #################### constants = map(GRASP, grasps) + map(POSE, poses) initial_atoms = [ ManipEq(initial_manip), HandEmpty(), ] + [ PoseEq(obj, pose) for obj, pose in problem.initial_poses.iteritems() ] goal_formula = And(ManipEq(initial_manip), *(PoseEq(obj, pose) for obj, pose in problem.goal_poses.iteritems())) stream_problem = STRIPStreamProblem(initial_atoms, goal_formula, actions + axioms, cond_streams, constants) if viewer: raw_input('Start?') search_fn = get_fast_downward('eager', max_time=10) #solve = lambda: incremental_planner(stream_problem, search=search_fn, frequency=1, waves=True, debug=False) solve = lambda: simple_focused(stream_problem, search=search_fn, max_level=INF, shared=False, debug=False, verbose=False) env.Lock() plan, universe = solve() env.Unlock() print SEPARATOR plan = convert_plan(plan) if plan is not None: print 'Success' for i, (action, args) in enumerate(plan): print i+1, action, args else: print 'Failure' #################### def step_path(traj): #for j, conf in enumerate(traj.path()): for j, conf in enumerate([traj.end()]): set_manipulator_values(manipulator, conf) raw_input('%s/%s) Step?'%(j, len(traj.path()))) if viewer and plan is not None: print SEPARATOR # Resets the initial state set_manipulator_values(manipulator, initial_manip.value) for obj, pose in problem.initial_poses.iteritems(): set_pose(bodies[obj], pose.value) for i, (action, args) in enumerate(plan): raw_input('\n%s/%s) Next?'%(i, len(plan))) if action.name == 'move': mq1, mq2, mt = args step_path(mt) elif action.name == 'pick': o, p, g, mq, gt = args step_path(gt.reverse()) robot.Grab(bodies[o]) step_path(gt) elif action.name == 'place': o, p, g, mq, gt = args step_path(gt.reverse()) robot.Release(bodies[o]) step_path(gt) else: raise ValueError(action.name) env.UpdatePublishedBodies() raw_input('Finish?')
def solve_tamp(env): viewer = env.GetViewer() is not None #problem = dantam(env) problem = dantam2(env) #problem = move_several_4(env) robot = env.GetRobots()[0] set_base_values(robot, (-.75, .2, -math.pi/2)) initialize_openrave(env, 'leftarm') manipulator = robot.GetActiveManipulator() cspace = CSpace.robot_arm(manipulator) base_manip = interfaces.BaseManipulation(robot, plannername=None, maxvelmult=None) #USE_GRASP_APPROACH = GRASP_APPROACHES.SIDE USE_GRASP_APPROACH = GRASP_APPROACHES.TOP #USE_GRASP_TYPE = GRASP_TYPES.TOUCH USE_GRASP_TYPE = GRASP_TYPES.GRASP bodies = {obj: env.GetKinBody(obj) for obj in problem.object_names} geom_hashes = {body.GetKinematicsGeometryHash() for body in bodies.values()} assert len(geom_hashes) == 1 # NOTE - assuming all objects has the same geometry all_bodies = bodies.values() body1 = all_bodies[-1] body2 = all_bodies[-2] if len(bodies) >= 2 else body1 grasps = get_grasps(env, robot, body1, USE_GRASP_APPROACH, USE_GRASP_TYPE)[:1] poses = problem.known_poses if problem.known_poses else [] ################################################## def enable_all(enable): for body in all_bodies: body.Enable(enable) def collision_free(pose1, pose2): body1.Enable(True) set_pose(body1, pose1.value) body2.Enable(True) set_pose(body2, pose2.value) return not env.CheckCollision(body1, body2) def grasp_env_cfree(mt, g): enable_all(False) # TODO - base config? body1.Enable(True) for conf in mt.path(): set_manipulator_values(manipulator, conf) # NOTE - can also grab set_pose(body1, object_trans_from_manip_trans(get_trans(manipulator), g.grasp_trans)) if env.CheckCollision(body1): return False return True def grasp_pose_cfree(mt, g, p): enable_all(False) # TODO - base config? body1.Enable(True) body2.Enable(True) set_pose(body2, p.value) for conf in mt.path(): set_manipulator_values(manipulator, conf) set_pose(body1, object_trans_from_manip_trans(get_trans(manipulator), g.grasp_trans)) if env.CheckCollision(body1, body2): return False return True ################################################## """ class CollisionStream(Stream): # TODO - could make an initial state version of this that doesn't need pose2 def get_values(self, **kwargs): self.enumerated = True pose1, pose2 = map(get_value, self.inputs) if collision_free(pose1, pose2): return [PoseCFree(pose1, pose2)] return [] #return [Movable()] # NOTE - only make movable when it fails a collision check CheckedInitial = Pred(POSE) # How should this be handled? The planner will need to revisit on the next state anyways class EnvCollisionStream(Stream): # NOTE - I could also make an environment OBJECT which I mutate. I'm kind of doing that now movable = [] def get_values(self, **kwargs): self.enumerated = True pose, = map(get_value, self.inputs) results = [CheckedInitial(pose)] for obj, pose2 in problem.initial_poses.iteritems(): if obj not in self.movable and collision_free(pose, pose2): pass #results.append(PoseCFree(pose, pose2)) else: self.movable.append(obj) results.append(PoseEq(obj, pose2)) #results.append(Movable(obj)) if results: pass # NOTE - I could make this fail if there is a collision # I could prevent the binding by directly adding CheckedInitial to the universe # In general, I probably can just mutate the problem however I see fit here return results """ ################################################## # NOTE - can do pose, approach manip, true approach traj, motion plan # NOTE - can make something that produces approach trajectories def get_manip_vector(pose, grasp): manip_trans, approach_vector = manip_from_pose_grasp(pose, grasp) #enable_all(False) #if manipulator.CheckEndEffectorCollision(manip_trans): # return None return ManipVector(manip_trans, approach_vector) def sample_ik(pose, grasp, base_conf): # TODO - make this return the grasp enable_all(False) set_base_values(robot, base_conf.value) body1.Enable(True) set_pose(body1, pose.value) manip_vector = get_manip_vector(pose, grasp) grasp_config = inverse_kinematics_helper(env, robot, manip_vector.manip_trans) # NOTE - maybe need to find all IK solutions #print manipulator.CheckEndEffectorCollision(manip_trans) if grasp_config is not None: yield [Config(grasp_config)] #traj = workspace_traj_helper(base_manip, approach_vector) def sample_grasp_traj(pose, grasp, base_conf): enable_all(False) set_base_values(robot, base_conf.value) body1.Enable(True) set_pose(body1, pose.value) manip_vector = get_manip_vector(pose, grasp) grasp_config = inverse_kinematics_helper(env, robot, manip_vector.manip_trans) # NOTE - maybe need to find all IK solutions if grasp_config is None: return set_manipulator_values(manipulator, grasp_config) grasp_traj = workspace_traj_helper(base_manip, manip_vector.approach_vector) if grasp_config is None: return yield [(Config(grasp_traj.end()), grasp_traj)] ################################################## # NOTE - can either include the held object in the traj or have a special condition that not colliding def sample_arm_traj(mq1, mq2, bq): # TODO - need to add holding back in yield None #enable_all(False) #with robot: # set_base_values(robot, bq.value) # pass # TODO - does it make sense to make a new stream for the biasing or to continuously just pass things # I suppose I could cache the state or full plan as context class MotionStream(Stream): # TODO - maybe make this produce the correct values num = 0 #def get_values(self, **kwargs): # self.enumerated = True # mq1, mq2, bq = map(get_value, self.inputs) # #mt = None # mt = MotionStream.num # MotionStream.num += 1 # Ensures all are unique # return [ManipMotion(mq1, mq2, bq, mt)] def sample_motion_plan(self, mq1, mq2, bq): set_manipulator_values(manipulator, mq1.value) set_base_values(robot, bq.value) return motion_plan(env, cspace, mq2.value, self_collisions=True) def get_values(self, universe, dependent_atoms=set(), **kwargs): mq1, mq2, bq = map(get_value, self.inputs) collision_atoms = filter(lambda atom: atom.predicate in [MTrajGraspCFree, MTrajPoseCFree], dependent_atoms) collision_params = {atom: atom.args[0] for atom in collision_atoms} grasp = None for atom in collision_atoms: if atom.predicate is MTrajGraspCFree: assert grasp is None # Can't have two grasps _, grasp = map(get_value, atom.args) placed = [] for atom in collision_atoms: if atom.predicate is MTrajPoseCFree: _, pose = map(get_value, atom.args) placed.append(pose) #placed, grasp = [], None print grasp, placed if placed or grasp: assert len(placed) <= len(all_bodies) # How would I handle many constraints on the same traj? enable_all(False) for b, p in zip(all_bodies, placed): b.Enable(True) set_pose(b, p.value) if grasp: assert grasp is None or len(placed) <= len(all_bodies)-1 set_pose(body1, object_trans_from_manip_trans(get_trans(manipulator), grasp.grasp_trans)) robot.Grab(body1) mt = self.sample_motion_plan(mq1, mq2, bq) if grasp: robot.Release(body1) if mt: self.enumerated = True # NOTE - if satisfies all constraints then won't need another. Not true. What if called with different grasps... # TODO - could always hash this trajectory for the current set of constraints bound_collision_atoms = [atom.instantiate({collision_params[atom]: MTRAJ(mt)}) for atom in collision_atoms] #bound_collision_atoms = [] return [ManipMotion(mq1, mq2, bq, mt)] + bound_collision_atoms raise ValueError() enable_all(False) mt = self.sample_motion_plan(mq1, mq2, bq) if mt: return [ManipMotion(mq1, mq2, bq, mt)] return [] ################################################## cond_streams = [ #MultiEasyGenStream(inputs=[O], outputs=[P], conditions=[], effects=[LegalPose(O, P)], generator=sample_poses), #EasyGenStream(inputs=[MQ, MQ2, BQ], outputs=[MT], conditions=[], # effects=[ManipMotion(MQ, MQ2, BQ, MT)], generator=sample_arm_traj), ClassStream(inputs=[MQ, MQ2, BQ], outputs=[MT], conditions=[], effects=[ManipMotion(MQ, MQ2, BQ, MT)], StreamClass=MotionStream, order=1, max_level=0), #MultiEasyGenStream(inputs=[P, G, BQ], outputs=[MQ], conditions=[], # effects=[Kin(P, G, BQ, MQ)], generator=sample_ik), EasyListGenStream(inputs=[P, G, BQ], outputs=[MQ, GT], conditions=[], effects=[GraspTraj(P, G, BQ, MQ, GT)], generator=sample_grasp_traj), #EasyTestStream(inputs=[O, P, T], conditions=[], effects=[CFree(O, P, T)], # test=collision_free, eager=True), EasyTestStream(inputs=[P, P2], conditions=[], effects=[PoseCFree(P, P2)], test=collision_free, eager=True), #ClassStream(inputs=[P, P2], conditions=[], outputs=[], # effects=[PoseCFree(P, P2)], StreamClass=CollisionStream, eager=True), EasyTestStream(inputs=[MT, P], conditions=[], effects=[MTrajPoseCFree(MT, P)], test=lambda mt, p: True, eager=True), EasyTestStream(inputs=[MT, G], conditions=[], effects=[MTrajGraspCFree(MT, G)], test=lambda mt, g: True, eager=True), EasyTestStream(inputs=[MT, G, P], conditions=[], effects=[MTrajGraspPoseCFree(MT, G, P)], test=lambda mt, g, p: True, eager=True), #ClassStream(inputs=[P], conditions=[], outputs=[], # effects=[CheckedInitial(P)], StreamClass=EnvCollisionStream), ] ################################################## constants = map(GRASP, grasps) + map(POSE, poses) initial_full = Config(get_full_config(robot)) initial_base = get_base_conf(initial_full) initial_manip = get_arm_conf(manipulator, initial_full) initial_atoms = [ BaseEq(initial_base), ManipEq(initial_manip), HandEmpty(), ] + [ PoseEq(obj, pose) for obj, pose in problem.initial_poses.iteritems() ] goal_formula = And(ManipEq(initial_manip), *(PoseEq(obj, pose) for obj, pose in problem.goal_poses.iteritems())) stream_problem = STRIPStreamProblem(initial_atoms, goal_formula, operators, cond_streams, constants) if viewer: raw_input('Start?') search_fn = get_fast_downward('eager') #plan, universe = incremental_planner(stream_problem, search=search_fn, frequency=INF, waves=True, debug=False) # 1 | 20 | 100 | INF #plan, _ = focused_planner(stream_problem, search=search_fn, frequency=1, waves=True, debug=False) # 1 | 20 | 100 | INF #plan, universe = simple_focused(stream_problem, search=search_fn, max_level=INF, debug=False, verbose=False) # 1 | 20 | 100 | INF #plan, _ = plan_focused(stream_problem, search=search_fn, debug=False) # 1 | 20 | 100 | INF from misc.profiling import run_profile, str_profile #solve = lambda: incremental_planner(stream_problem, search=search_fn, frequency=INF, waves=True, debug=False) solve = lambda: simple_focused(stream_problem, search=search_fn, max_level=INF, shared=False, debug=False, verbose=True) #with env: env.Lock() (plan, universe), prof = run_profile(solve) env.Unlock() print SEPARATOR universe.print_domain_statistics() universe.print_statistics() print SEPARATOR print str_profile(prof) print SEPARATOR plan = convert_plan(plan) if plan is not None: print 'Success' for i, (action, args) in enumerate(plan): print i+1, action, args else: print 'Failure' ################################################## def step_path(traj): #for j, conf in enumerate(traj.path()): for j, conf in enumerate([traj.end()]): set_manipulator_values(manipulator, conf) raw_input('%s/%s) Step?'%(j, len(traj.path()))) if viewer and plan is not None: print SEPARATOR # Resets the initial state open_gripper2(manipulator) set_base_values(robot, initial_base.value) set_manipulator_values(manipulator, initial_manip.value) for obj, pose in problem.initial_poses.iteritems(): set_pose(bodies[obj], pose.value) for i, (action, args) in enumerate(plan): raw_input('\n%s/%s) Next?'%(i, len(plan))) if action.name == 'move_arm': mq1, mq2, bq, mt = args #set_manipulator_values(manipulator, mq2.value) step_path(mt) elif action.name == 'pick': #o, p, q, mq, bq = args o, p, g, mq, bq, gt = args step_path(gt.reverse()) #grasp_gripper2(manipulator, g) # NOTE - g currently isn't a real grasp robot.Grab(bodies[o]) step_path(gt) elif action.name == 'place': #o, p, q, mq, bq = args o, p, g, mq, bq, gt = args step_path(gt.reverse()) robot.Release(bodies[o]) #open_gripper2(manipulator) step_path(gt) else: raise ValueError(action.name) env.UpdatePublishedBodies() raw_input('Finish?')
def feasible_pick_place(env, robot, obj, grasps, approach_config, do_motion_planning): t0 = time() base_manip = interfaces.BaseManipulation(robot, plannername=None, maxvelmult=None) #base_manip = interfaces.BaseManipulation(robot, plannername=None, maxvelmult=None) print time() - t0 #t0 = time() #task_manip = interfaces.TaskManipulation(robot, plannername=None, maxvelmult=None, graspername=None) #task_manip = interfaces.TaskManipulation(robot, plannername=None, maxvelmult=None, graspername=None) #print time() - t0 #print # Slight overhead but it appears you can just keep creating them #0.000910043716431 #0.000546932220459 pose = Pose(get_pose(obj)) #env.Remove(obj) # NOTE - I'm just testing this now for grasp in grasps: manip_trans, approach_vector = manip_from_pose_grasp(pose, grasp) set_config(robot, approach_config, robot.GetActiveManipulator().GetArmIndices()) if env.CheckCollision(robot) or robot.CheckSelfCollision(): print 'Collision failure' #rospy.loginfo("Failed collision") continue #DrawAxes(env, manip_trans) # TODO - OpenRAVE bug #print grasp.grasp_trans #handles = draw_axes(env, get_trans(obj)) #handles = draw_axes(env, manip_trans) #raw_input('Continue?') #grasp_config = inverse_kinematics_helper(env, robot, manip_trans) # NOTE - maybe need to find all IK solutions grasp_config = solve_inverse_kinematics_exhaustive(env, robot, manip_trans) if grasp_config is None: print 'IK failure' #rospy.loginfo("Failed IK") continue set_config(robot, grasp_config, get_active_arm_indices(robot)) #approach_config = get_full_config(robot) traj, arm_traj = None, None if do_motion_planning: #traj = vector_traj_helper(env, robot, approach_vector) traj = workspace_traj_helper(base_manip, approach_vector) if traj is None: print 'Vec traj failure' continue set_config(robot, traj.end(), get_active_arm_indices(robot)) #vector_config = oracle.get_robot_config() arm_traj = motion_plan(env, CSpace.robot_arm(get_manipulator(robot)), approach_config, self_collisions=True) #arm_traj = manip_traj_helper(base_manip, approach_config, max_iterations=25, max_tries=2) if arm_traj is None: print 'Approach traj failure' continue # TODO - need to do reverse trajectory return grasp_config, traj, arm_traj return None
def process_move_head(robot, q1, q2): cspace = CSpace.robot_manipulator(robot, 'head') h_traj = PathTrajectory(cspace, [q1.value, q2.value]) h_traj.traj() return [h_traj]
def solve_tamp(env): viewer = env.GetViewer() is not None problem = PROBLEM(env) robot = env.GetRobots()[0] set_base_values(robot, (-.75, .2, -math.pi / 2)) initialize_openrave(env, ARM) manipulator = robot.GetActiveManipulator() cspace = CSpace.robot_arm(manipulator) base_manip = interfaces.BaseManipulation(robot, plannername=None, maxvelmult=None) bodies = {obj: env.GetKinBody(obj) for obj in problem.object_names} geom_hashes = { body.GetKinematicsGeometryHash() for body in bodies.values() } assert len( geom_hashes) == 1 # NOTE - assuming all objects has the same geometry all_bodies = bodies.values() body1 = all_bodies[-1] body2 = all_bodies[-2] if len(bodies) >= 2 else body1 grasps = get_grasps(env, robot, body1, USE_GRASP_APPROACH, USE_GRASP_TYPE)[:1] poses = problem.known_poses if problem.known_poses else [] open_gripper2(manipulator) initial_manip = get_arm_conf(manipulator, Config(get_full_config(robot))) def enable_all(enable): for body in all_bodies: body.Enable(enable) #################### def cfree_pose_pose(pose1, pose2): body1.Enable(True) set_pose(body1, pose1.value) body2.Enable(True) set_pose(body2, pose2.value) return not env.CheckCollision(body1, body2) def cfree_gtraj_pose(gt, p): return cfree_mtraj_pose(gt, p) and cfree_mtraj_grasp_pose( gt, gt.grasp, p) #################### def cfree_mtraj_grasp(mt, g): enable_all(False) body1.Enable(True) for conf in mt.path(): set_manipulator_values(manipulator, conf) # NOTE - can also grab set_pose( body1, object_trans_from_manip_trans(get_trans(manipulator), g.grasp_trans)) if env.CheckCollision(body1): return False return True def cfree_mtraj_pose(mt, p): enable_all(False) body2.Enable(True) set_pose(body2, p.value) for conf in mt.path(): set_manipulator_values(manipulator, conf) if env.CheckCollision(body2): return False return True def cfree_mtraj_grasp_pose(mt, g, p): enable_all(False) body1.Enable(True) body2.Enable(True) set_pose(body2, p.value) for conf in mt.path(): set_manipulator_values(manipulator, conf) set_pose( body1, object_trans_from_manip_trans(get_trans(manipulator), g.grasp_trans)) if env.CheckCollision(body1, body2): return False return True #################### def sample_grasp_traj(pose, grasp): enable_all(False) body1.Enable(True) set_pose(body1, pose.value) manip_trans, approach_vector = manip_from_pose_grasp(pose, grasp) grasp_config = inverse_kinematics_helper(env, robot, manip_trans) if grasp_config is None: return set_manipulator_values(manipulator, grasp_config) robot.Grab(body1) grasp_traj = workspace_traj_helper(base_manip, approach_vector) robot.Release(body1) if grasp_traj is None: return grasp_traj.grasp = grasp yield [(Config(grasp_traj.end()), grasp_traj)] class MotionStream(Stream): def get_values(self, universe, dependent_atoms=set(), **kwargs): mq1, mq2 = map(get_value, self.inputs) collision_atoms = filter( lambda atom: atom.predicate in [CFreeMTrajGrasp, CFreeMTrajPose], dependent_atoms) collision_params = {atom: atom.args[0] for atom in collision_atoms} grasp = None for atom in collision_atoms: if atom.predicate is CFreeMTrajGrasp: assert grasp is None # Can't have two grasps _, grasp = map(get_value, atom.args) placed = [] for atom in collision_atoms: if atom.predicate is CFreeMTrajPose: _, pose = map(get_value, atom.args) placed.append(pose) #placed, grasp = [], None #print grasp, placed if placed or grasp: assert len(placed) <= len(all_bodies) enable_all(False) for b, p in zip(all_bodies, placed): b.Enable(True) set_pose(b, p.value) if grasp: assert grasp is None or len(placed) <= len(all_bodies) - 1 set_pose( body1, object_trans_from_manip_trans(get_trans(manipulator), grasp.grasp_trans)) robot.Grab(body1) set_manipulator_values(manipulator, mq1.value) mt = motion_plan(env, cspace, mq2.value, self_collisions=True) if grasp: robot.Release(body1) if mt: self.enumerated = True # NOTE - if satisfies all constraints then won't need another. Not true. What if called with different grasps... # TODO - could always hash this trajectory for the current set of constraints bound_collision_atoms = [ atom.instantiate({collision_params[atom]: MTRAJ(mt)}) for atom in collision_atoms ] #bound_collision_atoms = [] return [ManipMotion(mq1, mq2, mt)] + bound_collision_atoms raise ValueError() enable_all(False) set_manipulator_values(manipulator, mq1.value) mt = motion_plan(env, cspace, mq2.value, self_collisions=True) if mt: return [ManipMotion(mq1, mq2, mt)] return [] #################### cond_streams = [ # Pick/place trajectory EasyListGenStream(inputs=[P, G], outputs=[MQ, GT], conditions=[], effects=[GraspMotion(P, G, MQ, GT)], generator=sample_grasp_traj), # Move trajectory ClassStream(inputs=[MQ, MQ2], outputs=[MT], conditions=[], effects=[ManipMotion(MQ, MQ2, MT)], StreamClass=MotionStream, order=1, max_level=0), # Pick/place collisions EasyTestStream(inputs=[P, P2], conditions=[], effects=[CFreePosePose(P, P2)], test=cfree_pose_pose, eager=True), EasyTestStream(inputs=[GT, P], conditions=[], effects=[CFreeGTrajPose(GT, P)], test=cfree_gtraj_pose), # Move collisions EasyTestStream(inputs=[MT, P], conditions=[], effects=[CFreeMTrajPose(MT, P)], test=cfree_mtraj_pose), EasyTestStream(inputs=[MT, G], conditions=[], effects=[CFreeMTrajGrasp(MT, G)], test=cfree_mtraj_grasp), EasyTestStream(inputs=[MT, G, P], conditions=[], effects=[CFreeMTrajGraspPose(MT, G, P)], test=cfree_mtraj_grasp_pose), ] #################### constants = map(GRASP, grasps) + map(POSE, poses) initial_atoms = [ ManipEq(initial_manip), HandEmpty(), ] + [PoseEq(obj, pose) for obj, pose in problem.initial_poses.iteritems()] goal_formula = And( ManipEq(initial_manip), *(PoseEq(obj, pose) for obj, pose in problem.goal_poses.iteritems())) stream_problem = STRIPStreamProblem(initial_atoms, goal_formula, actions + axioms, cond_streams, constants) if viewer: raw_input('Start?') search_fn = get_fast_downward('eager') #plan, universe = incremental_planner(stream_problem, search=search_fn, frequency=INF, waves=True, debug=False) # 1 | 20 | 100 | INF #plan, _ = focused_planner(stream_problem, search=search_fn, frequency=1, waves=True, debug=False) # 1 | 20 | 100 | INF #plan, universe = simple_focused(stream_problem, search=search_fn, max_level=INF, debug=False, verbose=False) # 1 | 20 | 100 | INF #plan, _ = plan_focused(stream_problem, search=search_fn, debug=False) # 1 | 20 | 100 | INF from misc.profiling import run_profile, str_profile #solve = lambda: incremental_planner(stream_problem, search=search_fn, frequency=INF, waves=True, debug=False) solve = lambda: simple_focused(stream_problem, search=search_fn, max_level=INF, shared=False, debug=False, verbose=False) #with env: env.Lock() (plan, universe), prof = run_profile(solve) env.Unlock() print SEPARATOR universe.print_domain_statistics() universe.print_statistics() print SEPARATOR print str_profile(prof) print SEPARATOR plan = convert_plan(plan) if plan is not None: print 'Success' for i, (action, args) in enumerate(plan): print i + 1, action, args else: print 'Failure' #################### def step_path(traj): #for j, conf in enumerate(traj.path()): for j, conf in enumerate([traj.end()]): set_manipulator_values(manipulator, conf) raw_input('%s/%s) Step?' % (j, len(traj.path()))) if viewer and plan is not None: print SEPARATOR # Resets the initial state set_manipulator_values(manipulator, initial_manip.value) for obj, pose in problem.initial_poses.iteritems(): set_pose(bodies[obj], pose.value) for i, (action, args) in enumerate(plan): raw_input('\n%s/%s) Next?' % (i, len(plan))) if action.name == 'move': mq1, mq2, mt = args step_path(mt) elif action.name == 'pick': o, p, g, mq, gt = args step_path(gt.reverse()) robot.Grab(bodies[o]) step_path(gt) elif action.name == 'place': o, p, g, mq, gt = args step_path(gt.reverse()) robot.Release(bodies[o]) step_path(gt) else: raise ValueError(action.name) env.UpdatePublishedBodies() raw_input('Finish?')