def stop_recording(self, dummy=None): '''Stops recording continuous motion''' self.busy = True if (self._demo_state == DemoState.RECORDING_DEMO): traj_step = ActionStep() traj_step.type = ActionStep.ARM_TRAJECTORY waited_time = Interaction._arm_trajectory.timing[0] for i in range(len(Interaction._arm_trajectory.timing)): Interaction._arm_trajectory.timing[i] -= waited_time Interaction._arm_trajectory.timing[i] += rospy.Duration(0.1) '''If motion was relative, record transformed pose''' traj_step.armTrajectory = ArmTrajectory( Interaction._arm_trajectory.rArm[:], Interaction._arm_trajectory.lArm[:], Interaction._arm_trajectory.timing[:], Interaction._arm_trajectory.rRefFrame, Interaction._arm_trajectory.lRefFrame, Interaction._arm_trajectory.rRefFrameObject, Interaction._arm_trajectory.lRefFrameObject) traj_step.gripperAction = GripperAction( self.arms.get_gripper_state(0), self.arms.get_gripper_state(1)) self.session.add_step_to_action(traj_step, self.world.get_frame_list()) Interaction._arm_trajectory = None Interaction._trajectory_start_time = None self.session.save_current_action() self.freeze_arm(0) self._demo_state = DemoState.HAS_RECORDED_DEMO Response.say(RobotSpeech.STOPPED_RECORDING) Response.perform_gaze_action(GazeGoal.NOD) else: Response.say(RobotSpeech.ERROR_NOT_RECORDING) Response.perform_gaze_action(GazeGoal.SHAKE) rospy.loginfo('Current state: ' + self._demo_state) self.busy = False
def replay_demonstration(self, dummy=None): '''Starts the execution of the current demonstration''' self.busy = True execution_z_offset = 0.00 if (self._demo_state == DemoState.HAS_RECORDED_DEMO): self.session.save_current_action() action = self.session.get_current_action() self.arms.start_execution(action, execution_z_offset) Response.say(RobotSpeech.STARTED_REPLAY) self._demo_state = DemoState.PLAYING_DEMO else: Response.say(RobotSpeech.ERROR_CANNOT_REPLAY) Response.perform_gaze_action(GazeGoal.SHAKE) rospy.loginfo('Current state: ' + self._demo_state) self.busy = False
def release_tool(self, arm_index): self.busy = True if (self._demo_state != DemoState.READY_TO_TAKE and self._demo_state != DemoState.PLAYING_DEMO and self._demo_state != DemoState.RECORDING_DEMO): self._move_to_arm_pose('take', 0, wait=True) self.arms.set_gripper_state(arm_index, GripperState.OPEN, wait=True) Response.say(RobotSpeech.TOOL_RELEASED) Response.perform_gaze_action(GazeGoal.GLANCE_RIGHT_EE) self._demo_state = DemoState.READY_TO_TAKE else: Response.perform_gaze_action(GazeGoal.SHAKE) Response.say(RobotSpeech.ERROR_NOT_IN_RELEASE_STATE) rospy.loginfo('Current state: ' + self._demo_state) self.busy = False
def default_response(self, responses): '''Default response to speech commands''' self.busy = True speech_resp = responses[0] gaze_resp = responses[1] # Speech response if (speech_resp != None): Response.say(speech_resp) Response.respond_with_sound(speech_resp) # Gaze response if (gaze_resp != None): Response.perform_gaze_action(gaze_resp) rospy.loginfo('Current state: ' + self._demo_state) self.busy = False
def take_tool(self, arm_index): '''Robot's response to TAKE_TOOL''' self._is_busy = True if self._demo_state == DemoState.READY_TO_TAKE: ## Robot closes the hand Arms.set_gripper_state(arm_index, GripperState.CLOSED, wait=True) ## Robot moves the hand near the camera to take a look at the tool self._move_to_arm_pose('look', arm_index, wait=True) self.tool_id = self.world.get_tool_id() if self.tool_id is None: ## Robot moves the arm back to the person can take the tool self._move_to_arm_pose('take', 0, wait=True) Response.say(RobotSpeech.ERROR_TOOL_NOT_RECOGNIZED) Response.perform_gaze_action(GazeGoal.SHAKE) self._demo_state = DemoState.NO_TOOL_NO_SURFACE else: self.session.new_action(self.tool_id) Response.say(RobotSpeech.RECOGNIZED_TOOL + str(self.tool_id)) self._demo_state = DemoState.HAS_TOOL_NO_SURFACE self.detect_surface() else: Response.say(RobotSpeech.ERROR_NOT_IN_TAKE_STATE) rospy.loginfo('Current state: ' + self._demo_state) self._is_busy = False
def _end_replay(self): '''Responses for when the action execution ends''' if (self.arms.status == ExecutionStatus.SUCCEEDED): if self._demo_state == DemoState.PLAYING_DEMO: Response.say(RobotSpeech.ENDED_REPLAY) Response.perform_gaze_action(GazeGoal.NOD) self._demo_state = DemoState.HAS_RECORDED_DEMO else: rospy.loginfo('Non-replay motion successful.') elif (self.arms.status == ExecutionStatus.PREEMPTED): if self._demo_state == DemoState.PLAYING_DEMO: Response.say(RobotSpeech.ERROR_PREEMPTED_REPLAY) Response.perform_gaze_action(GazeGoal.SHAKE) self._demo_state = DemoState.HAS_RECORDED_DEMO else: rospy.loginfo('Non-replay motion pre-empted.') else: if self._demo_state == DemoState.PLAYING_DEMO: Response.say(RobotSpeech.ERROR_REPLAY_NOT_POSSIBLE) Response.perform_gaze_action(GazeGoal.SHAKE) self._demo_state = DemoState.HAS_RECORDED_DEMO else: rospy.loginfo('Non-replay motion has no IK.') self.arms.status = ExecutionStatus.NOT_EXECUTING
def start_recording(self, dummy=None): '''Starts recording continuous motion''' self.busy = True if (self._demo_state == DemoState.READY_FOR_DEMO or self._demo_state == DemoState.HAS_RECORDED_DEMO): Interaction._arm_trajectory = ArmTrajectory() Interaction._trajectory_start_time = rospy.Time.now() if self.session.n_frames() > 0: self.session.clear_current_action() self.relax_arm(0) self._demo_state = DemoState.RECORDING_DEMO Response.say(RobotSpeech.STARTED_RECORDING) Response.perform_gaze_action(GazeGoal.NOD) elif (self._demo_state == DemoState.RECORDING_DEMO): Response.perform_gaze_action(GazeGoal.SHAKE) Response.say(RobotSpeech.ERROR_ALREADY_RECORDING) else: Response.perform_gaze_action(GazeGoal.SHAKE) Response.say(RobotSpeech.ERROR_NOT_READY_TO_RECORD) rospy.loginfo('Current state: ' + self._demo_state) self.busy = False
def __init__(self): self.arms = Arms() self.world = World() self.session = Session(object_list=self.world.get_frame_list(), is_debug=True) self._viz_publisher = rospy.Publisher('visualization_marker_array', MarkerArray) self._demo_state = None self._is_busy = True rospy.Subscriber('recognized_command', Command, self.speech_command_cb) rospy.Subscriber('gui_command', GuiCommand, self.gui_command_cb) self.responses = { Command.TEST_MICROPHONE: Response(self.default_response, [RobotSpeech.TEST_RESPONSE, GazeGoal.NOD]), Command.TAKE_TOOL: Response(self.take_tool, 0), Command.RELEASE_TOOL: Response(self.release_tool, 0), Command.START_RECORDING: Response(self.start_recording, None), Command.STOP_RECORDING: Response(self.stop_recording, None), Command.REPLAY_DEMONSTRATION: Response(self.replay_demonstration, None) Command.DETECT_SURFACE: Response(self.detect_surface, None) } rospy.loginfo('Will wait until arms ready to respond.') while ((self.arms.get_ee_state(0) is None) or (self.arms.get_ee_state(1) is None)): time.sleep(0.1) rospy.loginfo('Starting to move to the initial pose.') # TODO: Make it possible to take with either hand self._move_to_arm_pose('take', 0) self._move_to_arm_pose('away', 1) self._wait_for_arms() self._demo_state = DemoState.READY_TO_TAKE Response.say(RobotSpeech.HAND_TOOL_REQUEST) Response.perform_gaze_action(GazeGoal.GLANCE_RIGHT_EE) self._is_busy = False rospy.loginfo('Interaction initialized.')
def _end_execution(self): '''Responses for when the action execution ends''' if (self.arms.status == ExecutionStatus.SUCCEEDED): Response.say(RobotSpeech.EXECUTION_ENDED) Response.perform_gaze_action(GazeGoal.NOD) elif (self.arms.status == ExecutionStatus.PREEMPTED): Response.say(RobotSpeech.EXECUTION_PREEMPTED) Response.perform_gaze_action(GazeGoal.SHAKE) else: Response.say(RobotSpeech.EXECUTION_ERROR_NOIK) Response.perform_gaze_action(GazeGoal.SHAKE) self.arms.status = ExecutionStatus.NOT_EXECUTING
def detect_surface(self): self._is_busy = True if self._demo_state == DemoState.HAS_TOOL_NO_SURFACE: ## Robot moves the arm away and looks at the surface self._move_to_arm_pose('away', 0, wait=True) self.surface = self.world.get_surface() if self.surface is None: Response.say(RobotSpeech.ERROR_NO_SURFACE) Response.perform_gaze_action(GazeGoal.SHAKE) else: Response.say(RobotSpeech.SURFACE_DETECTED) self._move_to_arm_pose('ready', arm_index, wait=True) Response.say(RobotSpeech.READY_FOR_DEMO) self._demo_state = DemoState.READY_FOR_DEMO self._is_busy = False