renamed controller to masterloop
This commit is contained in:
@@ -7,7 +7,7 @@ import rospy
|
||||
import tf
|
||||
from naoqi import ALProxy
|
||||
|
||||
from controller import inform_controller_factory
|
||||
from masterloop import inform_masterloop_factory
|
||||
|
||||
|
||||
FW = None
|
||||
@@ -40,7 +40,7 @@ def global_init():
|
||||
RR = n_way(cz, x['rr'], 2), x['rr']
|
||||
|
||||
|
||||
_inform_controller = inform_controller_factory('walker')
|
||||
_inform_masterloop = inform_masterloop_factory('walker')
|
||||
|
||||
|
||||
def _speed(pos, interval):
|
||||
@@ -58,7 +58,7 @@ def _speed(pos, interval):
|
||||
if __name__ == '__main__':
|
||||
rospy.init_node('walker')
|
||||
global_init()
|
||||
rospy.wait_for_service('inform_controller')
|
||||
rospy.wait_for_service('inform_masterloop')
|
||||
ll = tf.TransformListener()
|
||||
mp = ALProxy('ALMotion', os.environ['NAO_IP'], 9559)
|
||||
mp.wakeUp()
|
||||
@@ -75,7 +75,7 @@ if __name__ == '__main__':
|
||||
|
||||
except Exception as e:
|
||||
mp.stopMove()
|
||||
_inform_controller('stop')
|
||||
_inform_masterloop('stop')
|
||||
continue
|
||||
|
||||
movement = [0, 0, 0]
|
||||
@@ -95,12 +95,12 @@ if __name__ == '__main__':
|
||||
|
||||
if not any(movement):
|
||||
rospy.logdebug('WALKER: STOP')
|
||||
_inform_controller('stop')
|
||||
_inform_masterloop('stop')
|
||||
# mp.move(0, 0, 0)
|
||||
mp.stopMove()
|
||||
continue
|
||||
|
||||
permission = _inform_controller('move')
|
||||
permission = _inform_masterloop('move')
|
||||
|
||||
if not permission:
|
||||
mp.stopMove()
|
||||
|
||||
Reference in New Issue
Block a user