renamed controller to masterloop
This commit is contained in:
@@ -17,7 +17,7 @@ find_package(catkin REQUIRED COMPONENTS
|
|||||||
add_service_files(
|
add_service_files(
|
||||||
DIRECTORY srv
|
DIRECTORY srv
|
||||||
FILES
|
FILES
|
||||||
InformController.srv
|
InformMasterloop.srv
|
||||||
Hands.srv
|
Hands.srv
|
||||||
)
|
)
|
||||||
|
|
||||||
@@ -41,7 +41,7 @@ include_directories(
|
|||||||
|
|
||||||
catkin_install_python(PROGRAMS
|
catkin_install_python(PROGRAMS
|
||||||
./script/calibrator.py
|
./script/calibrator.py
|
||||||
./script/controller.py
|
./script/masterloop.py
|
||||||
./script/walker.py
|
./script/walker.py
|
||||||
./script/fall_detector.py
|
./script/fall_detector.py
|
||||||
./script/imitator.py
|
./script/imitator.py
|
||||||
|
|||||||
@@ -8,7 +8,7 @@
|
|||||||
output="screen"/>
|
output="screen"/>
|
||||||
<node name="speech_server" pkg="teleoperation" type="speech_server.py"
|
<node name="speech_server" pkg="teleoperation" type="speech_server.py"
|
||||||
output="screen"/>
|
output="screen"/>
|
||||||
<node name="controller" pkg="teleoperation" type="controller.py"
|
<node name="masterloop" pkg="teleoperation" type="masterloop.py"
|
||||||
output="screen"/>
|
output="screen"/>
|
||||||
<node name="hand_ler" pkg="teleoperation" type="hand_ler.py"/>
|
<node name="hand_ler" pkg="teleoperation" type="hand_ler.py"/>
|
||||||
<node name="imitator" pkg="teleoperation" type="imitator.py"
|
<node name="imitator" pkg="teleoperation" type="imitator.py"
|
||||||
|
|||||||
@@ -9,11 +9,11 @@ import actionlib
|
|||||||
import numpy as np
|
import numpy as np
|
||||||
from naoqi import ALProxy
|
from naoqi import ALProxy
|
||||||
|
|
||||||
from controller import inform_controller_factory
|
from masterloop import inform_masterloop_factory
|
||||||
from teleoperation.msg import RequestSpeechAction, RequestSpeechGoal
|
from teleoperation.msg import RequestSpeechAction, RequestSpeechGoal
|
||||||
|
|
||||||
|
|
||||||
_inform_controller = inform_controller_factory('calibrator')
|
_inform_masterloop = inform_masterloop_factory('calibrator')
|
||||||
|
|
||||||
|
|
||||||
def calibration():
|
def calibration():
|
||||||
|
|||||||
@@ -4,16 +4,17 @@ import os
|
|||||||
import rospy
|
import rospy
|
||||||
import numpy as np
|
import numpy as np
|
||||||
|
|
||||||
import sys
|
|
||||||
from naoqi import ALProxy
|
from naoqi import ALProxy
|
||||||
import motion
|
import motion
|
||||||
|
|
||||||
motionProxy = 0
|
|
||||||
|
mp = None
|
||||||
|
|
||||||
|
|
||||||
def get_transform(joint):
|
def get_transform(joint):
|
||||||
frame = motion.FRAME_TORSO
|
frame = motion.FRAME_TORSO
|
||||||
useSensorValues = True
|
useSensorValues = True
|
||||||
result = motionProxy.getTransform(joint,frame,useSensorValues)
|
result = mp.getTransform(joint,frame,useSensorValues)
|
||||||
result = np.matrix(result)
|
result = np.matrix(result)
|
||||||
print result
|
print result
|
||||||
result = np.reshape(result, (4,4))
|
result = np.reshape(result, (4,4))
|
||||||
@@ -25,15 +26,15 @@ def cartesian_position(joint):
|
|||||||
print 'function'
|
print 'function'
|
||||||
frame = motion.FRAME_TORSO
|
frame = motion.FRAME_TORSO
|
||||||
useSensorValues = True
|
useSensorValues = True
|
||||||
result = motionProxy.getPosition(joint, frame, useSensorValues)
|
result = mp.getPosition(joint, frame, useSensorValues)
|
||||||
#print result
|
#print result
|
||||||
return np.array(result[:3])
|
return np.array(result[:3])
|
||||||
|
|
||||||
|
|
||||||
def jacobian():
|
def jacobian():
|
||||||
|
# get current positions
|
||||||
# get current positions/ accordint to control figure these values should actually come from the
|
# according to control figure these values should actually come
|
||||||
# integration step in the previous first control loop
|
# from the integration step in the previous first control loop
|
||||||
|
|
||||||
end_position = cartesian_position('LArm')
|
end_position = cartesian_position('LArm')
|
||||||
|
|
||||||
@@ -55,13 +56,20 @@ def jacobian():
|
|||||||
|
|
||||||
# get basis vectors of jacobian
|
# get basis vectors of jacobian
|
||||||
|
|
||||||
shoulder_basis = np.cross(shoulder_axis[:3].flatten(), end_position - shoulder_position)
|
shoulder_basis = np.cross(shoulder_axis[:3].flatten(),
|
||||||
bicep_basis = np.cross(bicep_axis[:3].flatten(), end_position - bicep_position)
|
end_position - shoulder_position)
|
||||||
elbow_basis = np.cross(elbow_axis[:3].flatten(), end_position - elbow_position)
|
bicep_basis = np.cross(bicep_axis[:3].flatten(),
|
||||||
forearm_basis = np.cross(forearm_axis[:3].flatten(), end_position - forearm_position)
|
end_position - bicep_position)
|
||||||
|
elbow_basis = np.cross(elbow_axis[:3].flatten(),
|
||||||
|
end_position - elbow_position)
|
||||||
|
forearm_basis = np.cross(forearm_axis[:3].flatten(),
|
||||||
|
end_position - forearm_position)
|
||||||
|
|
||||||
# build jacobian matrix
|
# build jacobian matrix
|
||||||
jacobian = np.concatenate([shoulder_basis, bicep_basis, elbow_basis, forearm_basis], axis=0).T
|
jacobian = np.concatenate(
|
||||||
|
[shoulder_basis, bicep_basis, elbow_basis, forearm_basis],
|
||||||
|
axis=0
|
||||||
|
).T
|
||||||
|
|
||||||
return jacobian
|
return jacobian
|
||||||
|
|
||||||
@@ -70,7 +78,7 @@ def pseudo_inverse(jacobian):
|
|||||||
return np.linalg.pinv(jacobian)
|
return np.linalg.pinv(jacobian)
|
||||||
|
|
||||||
|
|
||||||
def reference_generator(p_d)
|
def reference_generator(p_d):
|
||||||
|
|
||||||
# calculate jacobian
|
# calculate jacobian
|
||||||
|
|
||||||
@@ -83,7 +91,7 @@ def reference_generator(p_d)
|
|||||||
return
|
return
|
||||||
|
|
||||||
|
|
||||||
def movement(e)
|
def movement(e):
|
||||||
|
|
||||||
# scale joint states with matrix K
|
# scale joint states with matrix K
|
||||||
|
|
||||||
@@ -95,8 +103,7 @@ def movement(e)
|
|||||||
|
|
||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
|
mp = ALProxy("ALMotion", os.environ['NAO_IP'], 9559)
|
||||||
motionProxy = ALProxy("ALMotion", os.environ['NAO_IP'], 9559)
|
|
||||||
jacob = jacobian()
|
jacob = jacobian()
|
||||||
print jacob
|
print jacob
|
||||||
jacob = pseudo_inverse(jacob)
|
jacob = pseudo_inverse(jacob)
|
||||||
@@ -115,6 +122,6 @@ if __name__ == '__main__':
|
|||||||
# movement
|
# movement
|
||||||
|
|
||||||
"""
|
"""
|
||||||
#rospy.init_node('cartesian_controller')
|
#rospy.init_node('cartesian_masterloop')
|
||||||
#rospy.spin()
|
#rospy.spin()
|
||||||
|
|
||||||
|
|||||||
@@ -4,14 +4,14 @@ import os
|
|||||||
import rospy
|
import rospy
|
||||||
from naoqi import ALProxy, ALBroker, ALModule
|
from naoqi import ALProxy, ALBroker, ALModule
|
||||||
|
|
||||||
from controller import inform_controller_factory
|
from masterloop import inform_masterloop_factory
|
||||||
|
|
||||||
|
|
||||||
fall_broker = None
|
fall_broker = None
|
||||||
almem = None
|
almem = None
|
||||||
|
|
||||||
|
|
||||||
_inform_controller = inform_controller_factory('fall_detector')
|
_inform_masterloop = inform_masterloop_factory('fall_detector')
|
||||||
|
|
||||||
|
|
||||||
class FallDetectorModule(ALModule):
|
class FallDetectorModule(ALModule):
|
||||||
@@ -21,10 +21,10 @@ class FallDetectorModule(ALModule):
|
|||||||
self.mp = ALProxy('ALMotion')
|
self.mp = ALProxy('ALMotion')
|
||||||
|
|
||||||
def on_robot_falling(self, *_args):
|
def on_robot_falling(self, *_args):
|
||||||
_inform_controller('falling')
|
_inform_masterloop('falling')
|
||||||
|
|
||||||
def on_robot_fallen(self, *_args):
|
def on_robot_fallen(self, *_args):
|
||||||
if not _inform_controller('fallen'):
|
if not _inform_masterloop('fallen'):
|
||||||
return
|
return
|
||||||
self.mp.rest()
|
self.mp.rest()
|
||||||
rospy.Rate(0.5).sleep()
|
rospy.Rate(0.5).sleep()
|
||||||
@@ -33,12 +33,12 @@ class FallDetectorModule(ALModule):
|
|||||||
while not pp.goToPosture('StandInit', 1.0):
|
while not pp.goToPosture('StandInit', 1.0):
|
||||||
pass
|
pass
|
||||||
rospy.Rate(1).sleep()
|
rospy.Rate(1).sleep()
|
||||||
_inform_controller('recovered')
|
_inform_masterloop('recovered')
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
rospy.init_node('fall_detector')
|
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,
|
fall_broker = ALBroker("fall_broker", "0.0.0.0", 0,
|
||||||
os.environ['NAO_IP'], 9559)
|
os.environ['NAO_IP'], 9559)
|
||||||
fall_detector = FallDetectorModule("fall_detector")
|
fall_detector = FallDetectorModule("fall_detector")
|
||||||
|
|||||||
@@ -9,10 +9,10 @@ import tf
|
|||||||
import numpy as np
|
import numpy as np
|
||||||
from naoqi import ALProxy
|
from naoqi import ALProxy
|
||||||
|
|
||||||
from controller import inform_controller_factory
|
from masterloop import inform_masterloop_factory
|
||||||
|
|
||||||
|
|
||||||
_inform_controller = inform_controller_factory('imitator')
|
_inform_masterloop = inform_masterloop_factory('imitator')
|
||||||
|
|
||||||
|
|
||||||
_FRAME_TORSO = 0
|
_FRAME_TORSO = 0
|
||||||
@@ -26,7 +26,7 @@ def _elbow(arm_):
|
|||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
rospy.init_node('imitator')
|
rospy.init_node('imitator')
|
||||||
rospy.wait_for_service('inform_controller')
|
rospy.wait_for_service('inform_masterloop')
|
||||||
ll = tf.TransformListener()
|
ll = tf.TransformListener()
|
||||||
am = ALProxy('ALAutonomousMoves', os.environ['NAO_IP'], 9559)
|
am = ALProxy('ALAutonomousMoves', os.environ['NAO_IP'], 9559)
|
||||||
am.setExpressiveListeningEnabled(False)
|
am.setExpressiveListeningEnabled(False)
|
||||||
@@ -43,7 +43,7 @@ if __name__ == '__main__':
|
|||||||
|
|
||||||
while not rospy.is_shutdown():
|
while not rospy.is_shutdown():
|
||||||
sleep(0.1)
|
sleep(0.1)
|
||||||
if not _inform_controller('imitate'):
|
if not _inform_masterloop('imitate'):
|
||||||
continue
|
continue
|
||||||
rospy.logdebug('IMITATOR: ACTIVE')
|
rospy.logdebug('IMITATOR: ACTIVE')
|
||||||
|
|
||||||
|
|||||||
@@ -4,7 +4,7 @@ from argparse import ArgumentParser
|
|||||||
import rospy
|
import rospy
|
||||||
import actionlib
|
import actionlib
|
||||||
|
|
||||||
from teleoperation.srv import InformController, InformControllerResponse
|
from teleoperation.srv import InformMasterloop, InformMasterloopResponse
|
||||||
from teleoperation.srv import Hands
|
from teleoperation.srv import Hands
|
||||||
from teleoperation.msg import RequestSpeechAction, RequestSpeechGoal
|
from teleoperation.msg import RequestSpeechAction, RequestSpeechGoal
|
||||||
|
|
||||||
@@ -79,17 +79,17 @@ def speech_done_cb(_, result):
|
|||||||
speech_in_progress = False
|
speech_in_progress = False
|
||||||
|
|
||||||
|
|
||||||
def inform_controller_factory(who):
|
def inform_masterloop_factory(who):
|
||||||
def inform_controller(what):
|
def inform_masterloop(what):
|
||||||
try:
|
try:
|
||||||
inform_controller = rospy.ServiceProxy('inform_controller',
|
inform_masterloop = rospy.ServiceProxy('inform_masterloop',
|
||||||
InformController)
|
InformMasterloop)
|
||||||
perm = inform_controller(who, what).permission
|
perm = inform_masterloop(who, what).permission
|
||||||
except rospy.service.ServiceException:
|
except rospy.service.ServiceException:
|
||||||
rospy.signal_shutdown('Controller is dead')
|
rospy.signal_shutdown('Masterloop is dead')
|
||||||
perm = False
|
perm = False
|
||||||
return perm
|
return perm
|
||||||
return inform_controller
|
return inform_masterloop
|
||||||
|
|
||||||
|
|
||||||
def handle_request(r):
|
def handle_request(r):
|
||||||
@@ -129,12 +129,12 @@ def handle_request(r):
|
|||||||
)
|
)
|
||||||
if _state_old != state:
|
if _state_old != state:
|
||||||
rospy.loginfo('{} -> {}'.format(_state_old, state))
|
rospy.loginfo('{} -> {}'.format(_state_old, state))
|
||||||
return InformControllerResponse(permission)
|
return InformMasterloopResponse(permission)
|
||||||
|
|
||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
|
|
||||||
rospy.init_node('controller')
|
rospy.init_node('masterloop')
|
||||||
ap = ArgumentParser()
|
ap = ArgumentParser()
|
||||||
ap.add_argument('-i', '--autoimitate',
|
ap.add_argument('-i', '--autoimitate',
|
||||||
help='Switch between moving and imitating automatically',
|
help='Switch between moving and imitating automatically',
|
||||||
@@ -144,7 +144,7 @@ if __name__ == '__main__':
|
|||||||
AI = args.autoimitate
|
AI = args.autoimitate
|
||||||
init_voc_state_speech()
|
init_voc_state_speech()
|
||||||
|
|
||||||
ic = rospy.Service('inform_controller', InformController, handle_request)
|
ic = rospy.Service('inform_masterloop', InformMasterloop, handle_request)
|
||||||
|
|
||||||
speech = actionlib.SimpleActionClient('speech_server',
|
speech = actionlib.SimpleActionClient('speech_server',
|
||||||
RequestSpeechAction)
|
RequestSpeechAction)
|
||||||
@@ -7,7 +7,7 @@ import rospy
|
|||||||
import tf
|
import tf
|
||||||
from naoqi import ALProxy
|
from naoqi import ALProxy
|
||||||
|
|
||||||
from controller import inform_controller_factory
|
from masterloop import inform_masterloop_factory
|
||||||
|
|
||||||
|
|
||||||
FW = None
|
FW = None
|
||||||
@@ -40,7 +40,7 @@ def global_init():
|
|||||||
RR = n_way(cz, x['rr'], 2), x['rr']
|
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):
|
def _speed(pos, interval):
|
||||||
@@ -58,7 +58,7 @@ def _speed(pos, interval):
|
|||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
rospy.init_node('walker')
|
rospy.init_node('walker')
|
||||||
global_init()
|
global_init()
|
||||||
rospy.wait_for_service('inform_controller')
|
rospy.wait_for_service('inform_masterloop')
|
||||||
ll = tf.TransformListener()
|
ll = tf.TransformListener()
|
||||||
mp = ALProxy('ALMotion', os.environ['NAO_IP'], 9559)
|
mp = ALProxy('ALMotion', os.environ['NAO_IP'], 9559)
|
||||||
mp.wakeUp()
|
mp.wakeUp()
|
||||||
@@ -75,7 +75,7 @@ if __name__ == '__main__':
|
|||||||
|
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
mp.stopMove()
|
mp.stopMove()
|
||||||
_inform_controller('stop')
|
_inform_masterloop('stop')
|
||||||
continue
|
continue
|
||||||
|
|
||||||
movement = [0, 0, 0]
|
movement = [0, 0, 0]
|
||||||
@@ -95,12 +95,12 @@ if __name__ == '__main__':
|
|||||||
|
|
||||||
if not any(movement):
|
if not any(movement):
|
||||||
rospy.logdebug('WALKER: STOP')
|
rospy.logdebug('WALKER: STOP')
|
||||||
_inform_controller('stop')
|
_inform_masterloop('stop')
|
||||||
# mp.move(0, 0, 0)
|
# mp.move(0, 0, 0)
|
||||||
mp.stopMove()
|
mp.stopMove()
|
||||||
continue
|
continue
|
||||||
|
|
||||||
permission = _inform_controller('move')
|
permission = _inform_masterloop('move')
|
||||||
|
|
||||||
if not permission:
|
if not permission:
|
||||||
mp.stopMove()
|
mp.stopMove()
|
||||||
|
|||||||
Reference in New Issue
Block a user