diff --git a/src/ai/basic_states.py b/src/ai/basic_states.py index a403973a..1dc18295 100644 --- a/src/ai/basic_states.py +++ b/src/ai/basic_states.py @@ -403,3 +403,16 @@ def callback(self, msg, userdata): c.levelOut() c.yawLeftAbsolute(userdata.heading_input) c.publish() + +class surface(SubscribeState): + def __init__(self): + SubscribeState.__init__(self, 'depth', Float32Stamped, self.surface_callback, outcomes=['success']) + + + def surface_callback(self, depth_message, userdata): + if depth_message.data < -0.1: + control = control_wrapper() + control.diveAbsolute(-0.1) + control.publish() + else: + self.exit('success') diff --git a/src/ai/smach_surface.py b/src/ai/smach_surface.py new file mode 100755 index 00000000..27ec74d0 --- /dev/null +++ b/src/ai/smach_surface.py @@ -0,0 +1,38 @@ +#!/usr/bin/python +import rospy +import smach +import smach_ros +from start_switch import start_switch +import roulette_states +import basic_states + +class surface_ai(smach.StateMachine): + def __init__(self): + smach.StateMachine.__init__(self, outcomes=['success']) + + with self: + smach.StateMachine.add('DIVE', basic_states.goToDepth(-0.5), + transitions={'success': 'MOVE_TO_PINGER', 'fail': 'FAIL', 'timeout': 'FAIL'}) + smach.StateMachine.add('MOVE_TO_PINGER', roulette_states.MoveToPinger(), + transitions={'success': 'SURFACE', 'fail': 'MOVE_TO_PINGER', + 'timeout': 'MOVE_TO_PINGER'}) + smach.StateMachine.add('SURFACE', basic_states.surface(), transitions={'success': 'success'}) + + +if __name__ == '__main__': + rospy.init_node('ai') + + while rospy.get_time() == 0: + continue + + + sm = smach.StateMachine(outcomes=['success']) + with sm: + smach.StateMachine.add('START_SWITCH', start_switch(), transitions={'success': 'SURFACE_TASK'}) + smach.StateMachine.add('SURFACE_TASK', surface_ai(), transitions={'success': 'success'}) + + + sis = smach_ros.IntrospectionServer('smach_server', sm, '/SM_ROOT') + sis.start() + outcomes = sm.execute() + sis.stop()