renamed controller to masterloop
This commit is contained in:
@@ -4,14 +4,14 @@ import os
|
||||
import rospy
|
||||
from naoqi import ALProxy, ALBroker, ALModule
|
||||
|
||||
from controller import inform_controller_factory
|
||||
from masterloop import inform_masterloop_factory
|
||||
|
||||
|
||||
fall_broker = None
|
||||
almem = None
|
||||
|
||||
|
||||
_inform_controller = inform_controller_factory('fall_detector')
|
||||
_inform_masterloop = inform_masterloop_factory('fall_detector')
|
||||
|
||||
|
||||
class FallDetectorModule(ALModule):
|
||||
@@ -21,10 +21,10 @@ class FallDetectorModule(ALModule):
|
||||
self.mp = ALProxy('ALMotion')
|
||||
|
||||
def on_robot_falling(self, *_args):
|
||||
_inform_controller('falling')
|
||||
_inform_masterloop('falling')
|
||||
|
||||
def on_robot_fallen(self, *_args):
|
||||
if not _inform_controller('fallen'):
|
||||
if not _inform_masterloop('fallen'):
|
||||
return
|
||||
self.mp.rest()
|
||||
rospy.Rate(0.5).sleep()
|
||||
@@ -33,12 +33,12 @@ class FallDetectorModule(ALModule):
|
||||
while not pp.goToPosture('StandInit', 1.0):
|
||||
pass
|
||||
rospy.Rate(1).sleep()
|
||||
_inform_controller('recovered')
|
||||
_inform_masterloop('recovered')
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
rospy.init_node('fall_detector')
|
||||
rospy.wait_for_service('inform_controller')
|
||||
rospy.wait_for_service('inform_masterloop')
|
||||
fall_broker = ALBroker("fall_broker", "0.0.0.0", 0,
|
||||
os.environ['NAO_IP'], 9559)
|
||||
fall_detector = FallDetectorModule("fall_detector")
|
||||
|
||||
Reference in New Issue
Block a user