def test_set_close(self): state = states.SetGripper(self.robot, self.arm_ds, 'close', self.entity_ds) self.assertEqual(state.execute(), "succeeded") self.robot.arms["leftArm"].send_gripper_goal.assert_called_once_with( 'close', mock.ANY, max_torque=mock.ANY) self.assertEqual(self.robot.arms["leftArm"].occupied_by, self.entity)
def __init__(self, robot, arm_designator, drop_bag_pose): """ :param robot: the robot with which to execute this state machine :param arm_designator: ArmDesignator resolving to Arm holding the bag to drop """ smach.StateMachine.__init__(self, outcomes=['done']) check_type(arm_designator, Arm) with self: smach.StateMachine.add('DROP_POSE', states.ArmToJointConfig( robot, arm_designator, drop_bag_pose), transitions={ 'succeeded': 'OPEN_AFTER_DROP', 'failed': 'OPEN_AFTER_DROP' }) smach.StateMachine.add('OPEN_AFTER_DROP', states.SetGripper( robot, arm_designator, gripperstate=GripperState.OPEN), transitions={ 'succeeded': 'RESET_ARM', 'failed': 'RESET_ARM' }) smach.StateMachine.add('RESET_ARM', states.ResetArms(robot), transitions={'done': 'done'})
def __init__(self, robot, arm_designator): """ :param robot: the robot with which to execute this state machine :param arm_designator: ArmDesignator resolving to Arm holding the bag to drop """ smach.StateMachine.__init__(self, outcomes=['succeeded','failed']) check_type(arm_designator, Arm) with self: smach.StateMachine.add( 'OPEN_BEFORE_DROP', states.SetGripper(robot, arm_designator, gripperstate='open'), transitions={'succeeded' : 'DROP_POSE', 'failed' : 'DROP_POSE'}) smach.StateMachine.add("DROP_POSE", states.ArmToJointConfig(robot, arm_designator, "drop_bag_pose"), transitions={'succeeded' :'RESET_ARM_OK', 'failed' :'RESET_ARM_FAIL'}) smach.StateMachine.add( 'RESET_ARM_OK', states.ResetArms(robot), transitions={'done' : 'succeeded'}) smach.StateMachine.add( 'RESET_ARM_FAIL', states.ResetArms(robot), transitions={'done' : 'failed'})
def setup_statemachine(robot): place_name = ds.EntityByIdDesignator(robot, id=challenge_knowledge.default_place, name="place_name") place_position = ds.LockingDesignator(ds.EmptySpotDesignator(robot, place_name, name="placement", area=challenge_knowledge.default_area), name="place_position") empty_arm_designator = ds.UnoccupiedArmDesignator(robot.arms, robot.rightArm, name="empty_arm_designator") # With the empty_arm_designator locked, it will ALWAYS resolve to the same arm (first resolve is cached), unless it is unlocked # For this challenge, unlocking is not needed bag_arm_designator = empty_arm_designator.lockable() bag_arm_designator.lock() # We don't actually grab something, so there is no need for an actual thing to grab current_item = ds.VariableDesignator(Entity("dummy", "dummy", "/{}/base_link".format(robot.robot_name), kdl_conversions.kdlFrameFromXYZRPY(0.6, 0, 0.5), None, {}, [], datetime.datetime.now()), name="current_item") sm = smach.StateMachine(outcomes=['Done','Aborted']) with sm: smach.StateMachine.add('INITIALIZE', states.Initialize(robot), transitions={'initialized': 'SET_INITIAL_POSE', 'abort': 'Aborted'}) smach.StateMachine.add('SET_INITIAL_POSE', states.SetInitialPose(robot, challenge_knowledge.starting_point), transitions={'done': 'FOLLOW_OPERATOR', "preempted": 'Aborted', 'error': 'FOLLOW_OPERATOR'}) # TODO: learn operator state needs to be added before follow # smach.StateMachine.add('WAIT_TO_FOLLOW', # WaitForOperatorCommand(robot, possible_commands=['follow', 'follow me']), # transitions={'success': 'FOLLOW_OPERATOR', # 'abort': 'Aborted'}) smach.StateMachine.add('ASK_FOLLOW_OR_REMEMBER', states.Say(robot, ["Are we at the car or should I follow you?"], block=True), transitions={'spoken': 'WAIT_TO_FOLLOW_OR_REMEMBER'}) smach.StateMachine.add('WAIT_TO_FOLLOW_OR_REMEMBER', WaitForOperatorCommand(robot, possible_commands=[ "follow", 'follow me', "here is the car", "stop following", "stop following me", ], commands_as_outcomes=True), transitions={'follow': 'FOLLOW_OPERATOR', 'follow me': 'FOLLOW_OPERATOR', 'here is the car': 'REMEMBER_CAR_LOCATION', 'stop following': 'REMEMBER_CAR_LOCATION', 'stop following me': 'REMEMBER_CAR_LOCATION', 'abort': 'Aborted'}) # Follow the operator until (s)he states that you have arrived at the "car". smach.StateMachine.add('FOLLOW_OPERATOR', states.FollowOperator(robot, operator_timeout=30, ask_follow=True, learn_face=True, replan=True), transitions={'stopped': 'ASK_FOLLOW_OR_REMEMBER', 'lost_operator': 'ASK_FOLLOW_OR_REMEMBER', 'no_operator': 'ASK_FOLLOW_OR_REMEMBER'}) smach.StateMachine.add('REMEMBER_CAR_LOCATION', StoreCarWaypoint(robot), transitions={'success': 'ASK_DESTINATION', 'abort': 'Aborted'}) smach.StateMachine.add('ASK_DESTINATION', states.Say(robot, ["Where should I bring the groceries?"], block=True), transitions={'spoken': 'WAIT_FOR_DESTINATION'}) smach.StateMachine.add('WAIT_FOR_DESTINATION', WaitForOperatorCommand(robot, possible_commands=challenge_knowledge.waypoints.keys(), commands_as_userdata=True), transitions={'success': 'GRAB_ITEM', 'abort': 'Aborted'}) # Grab the item (bag) the operator hands to the robot, when they are at the "car". smach.StateMachine.add('GRAB_ITEM', GrabItem(robot, bag_arm_designator, current_item), transitions={'succeeded': 'ARM_DRIVING_POSE', 'timeout': 'BACKUP_CLOSE_GRIPPER', # For now in simulation timeout is considered a succes. 'failed': 'BACKUP_CLOSE_GRIPPER'}, remapping={'target_room_in': 'command_recognized', 'target_room_out': 'target_room'}) smach.StateMachine.add('BACKUP_CLOSE_GRIPPER', states.SetGripper(robot, bag_arm_designator, gripperstate=GripperState.CLOSE), transitions={'succeeded': 'ARM_DRIVING_POSE', 'failed': 'ARM_DRIVING_POSE'}) smach.StateMachine.add('ARM_DRIVING_POSE', states.ArmToJointConfig(robot, bag_arm_designator, 'driving_bag_pose'), transitions={'succeeded': 'SAY_GOING_TO_ROOM', 'failed': 'SAY_GOING_TO_ROOM'}) smach.StateMachine.add('SAY_GOING_TO_ROOM', states.Say(robot, ["Let me bring in your groceries", "Helping you carry stuff", "I'm going back inside"], block=True), transitions={'spoken': 'GOTO_DESTINATION'}) smach.StateMachine.add('GOTO_DESTINATION', NavigateToRoom(robot), transitions={'arrived': 'PUTDOWN_ITEM', 'unreachable': 'PUTDOWN_ITEM', # implement avoid obstacle behaviour later 'goal_not_defined': 'Aborted'}) # Put the item (bag) down when the robot has arrived at the "drop-off" location (house). smach.StateMachine.add('PUTDOWN_ITEM', DropBagOnGround(robot, bag_arm_designator), transitions={'succeeded': 'ASKING_FOR_HELP', 'failed': 'ASKING_FOR_HELP'}) smach.StateMachine.add('ASKING_FOR_HELP', #TODO: look and then face new operator states.Say(robot, "Please follow me and help me carry groceries into the house"), transitions={'spoken': 'GOTO_CAR'}) #transitions={'success': 'GOTO_CAR', # 'abort': 'Aborted'}) smach.StateMachine.add('GOTO_CAR', states.NavigateToWaypoint(robot, ds.EntityByIdDesignator(robot, id=challenge_knowledge.waypoint_car['id']), challenge_knowledge.waypoint_car['radius']), # TODO: detect closed door transitions={'unreachable': 'OPEN_DOOR', 'arrived': 'AT_END', 'goal_not_defined': 'Aborted'}) smach.StateMachine.add('OPEN_DOOR', #TODO: implement functionality states.Say(robot, "Please open the door for me"), transitions={'spoken': 'GOTO_CAR'}) #transitions={'success': 'GOTO_CAR', # 'abort': 'Aborted'}) smach.StateMachine.add('AT_END', states.Say(robot, ["We arrived at the car, goodbye", "You have reached your destination, goodbye", "The car is right here, see you later!"], block=True), transitions={'spoken': 'Done'}) ds.analyse_designators(sm, "help_me_carry") return sm
def test_set_open(self): state = states.SetGripper(self.robot, self.arm_ds, 'open') self.assertEqual(state.execute(), "succeeded") self.robot.arms["leftArm"].send_gripper_goal.assert_called_once_with( 'open', mock.ANY, max_torque=mock.ANY)
def test_invalid_arm_designator(self): invalid_arm_ds = ds.ArmDesignator( self.robot, {'required_arm_name': 'there_is_no_arm_with_this_name'}) state = states.SetGripper(self.robot, invalid_arm_ds, 'close') self.assertEqual(state.execute(), "failed")
def __init__(self, robot): smach.StateMachine.__init__(self, outcomes=['Done', 'Aborted']) msg = "\n".join([ "==============================================", "== CHALLENGE HELP ME CARRY ==", "==============================================" ]) rospy.loginfo("\n" + msg) self.target_destination = ds.EntityByIdDesignator( robot, id=challenge_knowledge.default_place) self.car_waypoint = ds.EntityByIdDesignator( robot, id=challenge_knowledge.waypoint_car['id']) self.empty_arm_designator = ds.UnoccupiedArmDesignator( robot, arm_properties={ "required_goals": [ "handover_to_human", "reset", challenge_knowledge.driving_bag_pose, challenge_knowledge.drop_bag_pose ], "required_gripper_types": [GripperTypes.GRASPING] }, name="empty_arm_designator") # With the empty_arm_designator locked, it will ALWAYS resolve to the same arm, unless it is unlocked. # For this challenge, unlocking is not needed. self.bag_arm_designator = self.empty_arm_designator.lockable() self.bag_arm_designator.lock() self.place_position = ds.LockingDesignator(EmptySpotDesignator( robot, self.target_destination, arm_designator=self.bag_arm_designator, name="placement", area=challenge_knowledge.default_area), name="place_position") # We don't actually grab something, so there is no need for an actual thing to grab self.current_item = ds.VariableDesignator(Entity( "dummy", "dummy", "/{}/base_link".format(robot.robot_name), kdl_conversions.kdl_frame_from_XYZRPY(0.6, 0, 0.5), None, {}, [], datetime.datetime.now()), name="current_item") with self: smach.StateMachine.add('INITIALIZE', states.Initialize(robot), transitions={ 'initialized': 'SET_INITIAL_POSE', 'abort': 'Aborted' }) smach.StateMachine.add('SET_INITIAL_POSE', states.SetInitialPose( robot, challenge_knowledge.starting_point), transitions={ 'done': 'FOLLOW_OPERATOR', "preempted": 'Aborted', 'error': 'FOLLOW_OPERATOR' }) # Follow the operator until (s)he states that you have arrived at the "car". smach.StateMachine.add('FOLLOW_OPERATOR', states.FollowOperator(robot, operator_timeout=30, ask_follow=True, learn_face=True, replan=True), transitions={ 'stopped': 'ASK_FOR_TASK', 'lost_operator': 'ASK_FOR_TASK', 'no_operator': 'ASK_FOR_TASK' }) smach.StateMachine.add('ASK_FOR_TASK', states.Say(robot, ["Are we at the car already?"], block=True, look_at_standing_person=True), transitions={'spoken': 'WAIT_FOR_TASK'}) smach.StateMachine.add( 'WAIT_FOR_TASK', hmc_states.WaitForOperatorCommand( robot, possible_commands=challenge_knowledge.commands.keys(), commands_as_outcomes=True), transitions={ 'no': 'FOLLOW_OPERATOR', 'yes': 'REMEMBER_CAR_LOCATION', 'abort': 'Aborted' }) smach.StateMachine.add('REMEMBER_CAR_LOCATION', hmc_states.StoreCarWaypoint(robot), transitions={ 'success': 'ASK_FOR_DESTINATION', 'abort': 'Aborted' }) smach.StateMachine.add( 'ASK_FOR_DESTINATION', states.Say(robot, ["Where should I bring the groceries?"], block=True, look_at_standing_person=True), transitions={'spoken': 'RECEIVE_DESTINATION'}) smach.StateMachine.add( 'RECEIVE_DESTINATION', hmc_states.WaitForOperatorCommand( robot, possible_commands=challenge_knowledge.destinations, commands_as_userdata=True, target=self.target_destination), transitions={ 'success': 'GRAB_ITEM', 'abort': 'Aborted' }) # Grab the item (bag) the operator hands to the robot, when they are at the "car". smach.StateMachine.add( 'GRAB_ITEM', states.HandoverFromHuman( robot, self.bag_arm_designator, "current_item", self.current_item, arm_configuration=challenge_knowledge.carrying_bag_pose), transitions={ 'succeeded': 'ARM_DRIVING_POSE', 'timeout': 'BACKUP_CLOSE_GRIPPER', # For now in simulation timeout is considered a success. 'failed': 'BACKUP_CLOSE_GRIPPER' }) smach.StateMachine.add('BACKUP_CLOSE_GRIPPER', states.SetGripper( robot, self.bag_arm_designator, gripperstate=GripperState.CLOSE), transitions={ 'succeeded': 'ARM_DRIVING_POSE', 'failed': 'ARM_DRIVING_POSE' }) smach.StateMachine.add('ARM_DRIVING_POSE', states.ArmToJointConfig( robot, self.bag_arm_designator, challenge_knowledge.driving_bag_pose), transitions={ 'succeeded': 'SAY_GOING_TO_ROOM', 'failed': 'SAY_GOING_TO_ROOM' }) smach.StateMachine.add( 'SAY_GOING_TO_ROOM', states.Say(robot, [ "Let me bring in your groceries", "Helping you carry stuff", "I'm going back inside" ], block=True, look_at_standing_person=True), transitions={'spoken': 'GOTO_DESTINATION'}) smach.StateMachine.add( 'GOTO_DESTINATION', states.NavigateToWaypoint( robot, self.target_destination, challenge_knowledge.default_target_radius), transitions={ 'arrived': 'PUTDOWN_ITEM', 'unreachable': 'GOTO_DESTINATION_BACKUP', # implement avoid obstacle behaviour later 'goal_not_defined': 'Aborted' }) smach.StateMachine.add( 'GOTO_DESTINATION_BACKUP', states.NavigateToWaypoint( robot, self.target_destination, challenge_knowledge.backup_target_radius), transitions={ 'arrived': 'PUTDOWN_ITEM', 'unreachable': 'PUTDOWN_ITEM', # implement avoid obstacle behaviour later 'goal_not_defined': 'Aborted' }) # Put the item (bag) down when the robot has arrived at the "drop-off" location (house). smach.StateMachine.add('PUTDOWN_ITEM', hmc_states.DropBagOnGround( robot, self.bag_arm_designator, challenge_knowledge.drop_bag_pose), transitions={'done': 'ASKING_FOR_HELP'}) smach.StateMachine.add( 'ASKING_FOR_HELP', # TODO: look and then face new operator states.Say( robot, "Please follow me and help me carry groceries into the house", block=True, look_at_standing_person=True), transitions={'spoken': 'GOTO_CAR'}) smach.StateMachine.add( 'GOTO_CAR', states.NavigateToWaypoint( robot, self.car_waypoint, challenge_knowledge.waypoint_car['radius']), # TODO: detect closed door transitions={ 'unreachable': 'OPEN_DOOR', 'arrived': 'AT_END', 'goal_not_defined': 'Aborted' }) smach.StateMachine.add( 'OPEN_DOOR', # TODO: implement functionality states.Say(robot, "Please open the door for me"), transitions={'spoken': 'GOTO_CAR'}) smach.StateMachine.add( 'AT_END', states.Say(robot, [ "We arrived at the car, goodbye", "You have reached your destination, goodbye", "The car is right here, see you later!" ], block=True, look_at_standing_person=True), transitions={'spoken': 'Done'}) ds.analyse_designators(self, "help_me_carry")
def grab_demo(robot): import smach import robot_smach_states as states robot.leftArm.reset_arm() robot.rightArm.reset_arm() robot.reasoner.reset() robot.reasoner.detach_all_from_gripper("/amigo/grippoint_left") robot.reasoner.detach_all_from_gripper("/amigo/grippoint_right") r = robot.reasoner r.query(r.load_database("tue_knowledge", 'prolog/locations.pl')) r.assertz(r.challenge("clean_up")) rospy.loginfo("Setting up state machine") sm = smach.StateMachine(outcomes=['Done', "Failed", "Aborted"]) search_query = Compound("point_of_interest", "Poi", Compound("point_3d", "X", "Y", "Z")) object_query = Compound("position", Compound( "point_3d", "X", "Y", "Z")) #I don't care a bout the type for now. with sm: smach.StateMachine.add('GET_OBJECT', states.GetObject(robot, robot.leftArm, search_query, object_query), transitions={ 'Done': 'DROPOFF_OBJECT', 'Failed': 'Failed', 'Aborted': 'Aborted', 'Timeout': 'Failed' }) query_dropoff_loc = Compound("point_of_interest", "trashbin1", Compound("point_3d", "X", "Y", "Z")) smach.StateMachine.add("DROPOFF_OBJECT", states.Gripper_to_query_position( robot, robot.leftArm, query_dropoff_loc), transitions={ 'succeeded': 'DROP_OBJECT', 'failed': 'Failed', 'target_lost': 'Failed' }) smach.StateMachine.add( 'DROP_OBJECT', states.SetGripper(robot, robot.leftArm, gripperstate=0), #open transitions={ 'succeeded': 'CLOSE_AFTER_DROP', 'failed': 'CLOSE_AFTER_DROP' }) smach.StateMachine.add( 'CLOSE_AFTER_DROP', states.SetGripper(robot, robot.leftArm, gripperstate=1), #close transitions={ 'succeeded': 'RESET_ARM', 'failed': 'RESET_ARM' }) smach.StateMachine.add( 'RESET_ARM', states.ArmToPose(robot, robot.leftArm, (-0.0830, -0.2178, 0.0000, 0.5900, 0.3250, 0.0838, 0.0800)), #Copied from demo_executioner NORMAL transitions={ 'done': 'GET_OBJECT', 'failed': 'Failed' }) rospy.loginfo("State machine set up, start execution...") #import pdb; pdb.set_trace() import smach_ros introserver = smach_ros.IntrospectionServer('server_name', sm, '/SM_ROOT_PRIMARY') introserver.start() result = sm.execute() introserver.stop() r.query(r.retractall(r.visited("X"))) r.query(r.retractall(r.unreachable("X"))) rospy.loginfo("State machine executed. Result: {0}".format(result))