everything seems to work together as expected

(if not perfectly)
This commit is contained in:
Pavel Lutskov
2019-01-29 12:07:17 +01:00
parent 2d0441306a
commit b6e7ab8aa4
7 changed files with 71 additions and 43 deletions

View File

@@ -23,6 +23,8 @@ def inform_controller_factory(who):
def handle_request(r):
module = r.module
message = r.message
_state_old = STATE
permission = False
global STATE
if module == 'walker':
@@ -30,12 +32,10 @@ def handle_request(r):
if STATE in ('idle', 'walk'):
STATE = 'walk'
permission = True
else:
permission = False
elif message == 'stop':
if STATE == 'walk':
STATE = 'idle'
permission = True
permission = True
elif module == 'fall_detector':
permission = True
@@ -48,28 +48,27 @@ def handle_request(r):
if message == 'imitate':
if STATE == 'imitate':
permission = True
else:
permission = False
elif module == 'speech_recognition':
if message == 'imitate':
if message == 'recognize':
if STATE in ('idle', 'imitate'):
permission = True
elif message == 'imitate':
if STATE == 'idle':
STATE = 'imitate'
permission = True
else:
permission = False
if message == 'stop':
elif message == 'stop':
if STATE == 'imitate':
STATE = 'idle'
permission = True
else:
permission = False
rospy.loginfo(
'Got request from %s to %s. Permission: %s. State is now: %s.' % (
rospy.logdebug(
'GOT REQUEST FROM %s TO %s.\nPERMISSION: %s.\nSTATE IS NOW: %s.' % (
module, message, permission, STATE
)
)
if _state_old != STATE:
rospy.loginfo('{} -> {}'.format(_state_old, STATE))
return InformControllerResponse(permission)

View File

@@ -18,6 +18,8 @@ if __name__ == '__main__':
rospy.init_node('imitator')
rospy.wait_for_service('inform_controller')
ll = tf.TransformListener()
am = ALProxy('ALAutonomousMoves', os.environ['NAO_IP'], 9559)
am.setExpressiveListeningEnabled(False)
mp = ALProxy('ALMotion', os.environ['NAO_IP'], 9559)
mp.wakeUp()
mp.setAngles(['LElbowRoll', 'RElbowRoll', 'LElbowYaw', 'RElbowYaw'],
@@ -27,7 +29,7 @@ if __name__ == '__main__':
sleep(0.1)
if not _inform_controller('imitate'):
continue
rospy.loginfo('IMITATOR: ACTIVE')
rospy.logdebug('IMITATOR: ACTIVE')
for i, eff in enumerate(['L',
'R'], 1):
try:
@@ -37,6 +39,7 @@ if __name__ == '__main__':
rospy.Time(0)
)
except Exception as e:
rospy.logwarn(e)
continue
sign = 1 if eff == 'L' else -1

View File

@@ -57,12 +57,6 @@ if __name__ == '__main__':
# print trans
# continue
permission = _inform_controller('move')
if not permission:
mp.stopMove()
continue
movement = [0, 0, 0]
#-1 1 -1 1
for i, dr in enumerate((BK, FW, RT, LT)):
@@ -74,12 +68,19 @@ if __name__ == '__main__':
break
if not any(movement):
rospy.loginfo('WALKER: STOP')
rospy.logdebug('WALKER: STOP')
_inform_controller('stop')
mp.move(0, 0, 0)
else:
rospy.loginfo('WALKER: TRANS: {}'.format(trans))
rospy.loginfo('WALKER: MOVMT: {}'.format(movement))
mp.moveToward(*movement)
continue
permission = _inform_controller('move')
if not permission:
mp.stopMove()
continue
rospy.loginfo('WALKER: TRANS: {}'.format(trans))
rospy.loginfo('WALKER: MOVMT: {}'.format(movement))
mp.moveToward(*movement)
mp.rest()