Revision 465c7ad7
client/python/hlrc_client/Middleware.py | ||
---|---|---|
85 | 85 |
def publish_gaze_target(self, gaze, blocking): |
86 | 86 |
self.die_virtual(sys._getframe().f_code.co_name) |
87 | 87 |
|
88 |
def publish_lookat_target(self, x, y, z, blocking, frame_id, roll): |
|
89 |
self.die_virtual(sys._getframe().f_code.co_name) |
|
90 |
|
|
88 | 91 |
def publish_mouth_target(self, mouth, blocking): |
89 | 92 |
self.die_virtual(sys._getframe().f_code.co_name) |
90 | 93 |
|
... | ... | |
143 | 146 |
self.gaze_target = gaze |
144 | 147 |
self.publish_gaze_target(gaze, blocking) |
145 | 148 |
|
149 |
def set_lookat_target(self, x, y, z, blocking=False, frame_id='', roll=0.0): |
|
150 |
"""set a gaze at a Cartesian position |
|
151 |
:param x,y,z: position to look at (in eyes frame or frame_id) |
|
152 |
:param roll: side-ways motion of head |
|
153 |
:param blocking: True if this call should block until execution finished on robot |
|
154 |
""" |
|
155 |
self.publish_lookat_target(x, y, z, blocking, frame_id, roll) |
|
156 |
|
|
146 | 157 |
####################################################################### |
147 | 158 |
#some get methods |
148 | 159 |
#def get_current_emotion(self): |
client/python/hlrc_client/MiddlewareROS.py | ||
---|---|---|
28 | 28 |
from Middleware import * |
29 | 29 |
import errno |
30 | 30 |
|
31 |
import roslib; |
|
32 | 31 |
import rospy |
33 | 32 |
import actionlib |
34 | 33 |
from hlrc_server.msg import * |
34 |
from geometry_msgs.msg import Point |
|
35 | 35 |
from actionlib_msgs.msg import GoalStatus |
36 | 36 |
|
37 | 37 |
class MiddlewareROS(Middleware): |
... | ... | |
86 | 86 |
self.gazetarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/gaze", gazetargetAction) |
87 | 87 |
self.gazetarget_client.wait_for_server() |
88 | 88 |
|
89 |
self.logger.debug("creating lookattarget action client") |
|
90 |
self.lookattarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/lookat", lookattargetAction) |
|
91 |
self.lookattarget_client.wait_for_server() |
|
92 |
|
|
89 | 93 |
self.logger.debug("creating mouthtarget action client") |
90 | 94 |
self.mouthtarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/mouth", mouthtargetAction) |
91 | 95 |
self.mouthtarget_client.wait_for_server() |
... | ... | |
196 | 200 |
|
197 | 201 |
self.logger.debug("gaze rpc done") |
198 | 202 |
|
203 |
def publish_lookat_target(self, x, y, z, blocking, frame_id='', roll=0.0): |
|
204 |
"""publish a gaze target via mw |
|
205 |
:param x,y,z: position to look at (in eyes frame or frame_id) |
|
206 |
:param roll: side-ways motion of head |
|
207 |
:param blocking: True if this call should block until execution finished on robot |
|
208 |
""" |
|
209 |
self.logger.debug("calling the gaze rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
|
210 |
|
|
211 |
# create a goal to send to the action server. |
|
212 |
goal = lookattargetGoal() |
|
213 |
goal.header.frame_id = frame_id |
|
214 |
goal.header.stamp = rospy.Time.now() |
|
215 |
|
|
216 |
p = Point() |
|
217 |
p.x = float(x) |
|
218 |
p.y = float(y) |
|
219 |
p.z = float(z) |
|
220 |
goal.point = p |
|
221 |
goal.roll = roll |
|
222 |
|
|
223 |
# send the goal to the server |
|
224 |
if blocking: |
|
225 |
# send and wait: |
|
226 |
state = self.lookattarget_client.send_goal_and_wait(goal, execute_timeout=rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT)) |
|
227 |
if state != GoalStatus.SUCCEEDED: |
|
228 |
self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name)) |
|
229 |
else: |
|
230 |
# non blocking, fire & forget |
|
231 |
self.lookattarget_client.send_goal(goal) |
|
232 |
|
|
233 |
self.logger.debug("lookat rpc done") |
|
234 |
|
|
199 | 235 |
def publish_mouth_target(self, mouth, blocking): |
200 | 236 |
"""publish a mouth target via mw |
201 | 237 |
:param mouth: mouth value to set |
client/python/hlrc_client/RobotController.py | ||
---|---|---|
41 | 41 |
# create nice and actually usable formatter and add it to the handler |
42 | 42 |
self.config_logger(loglevel) |
43 | 43 |
|
44 |
#store |
|
44 |
# store
|
|
45 | 45 |
self.scope = scope |
46 | 46 |
self.mw = mw_name |
47 | 47 |
self.loglevel = loglevel |
48 | 48 |
|
49 | 49 |
self.middleware = None |
50 | 50 |
|
51 |
|
|
52 | 51 |
if (self.mw.upper() == "RSB"): |
53 | 52 |
self.logger.info("creating new middleware connection via RSB") |
54 | 53 |
try: |
... | ... | |
57 | 56 |
self.logger.error("failed to import RSB or the necessary data types: {}".format(e)) |
58 | 57 |
sys.exit(errno.EINVAL) |
59 | 58 |
|
60 |
#import worked, safe to intantiate RSB mw now |
|
59 |
# import worked, safe to intantiate RSB mw now
|
|
61 | 60 |
self.middleware = MiddlewareRSB(self.scope, self.loglevel) |
62 | 61 |
|
63 | 62 |
elif (self.mw.upper() == "ROS"): |
... | ... | |
68 | 67 |
self.logger.error("failed to import ROS or the necessary data types: {}".format(e)) |
69 | 68 |
sys.exit(errno.EINVAL) |
70 | 69 |
|
71 |
#import worked, safe to intantiate RSB mw now |
|
70 |
# import worked, safe to intantiate RSB mw now
|
|
72 | 71 |
self.middleware = MiddlewareROS(self.scope, self.loglevel) |
73 | 72 |
else: |
74 | 73 |
self.logger.error("invalid middleware requested (%s). supported: {ROS, RSB}\n\n" % (self.mw)) |
... | ... | |
88 | 87 |
""" |
89 | 88 |
formatter = logging.Formatter('%(asctime)s %(name)-30s %(levelname)-8s > %(message)s') |
90 | 89 |
ch = logging.StreamHandler() |
91 |
#ch.setLevel(level) |
|
90 |
# ch.setLevel(level)
|
|
92 | 91 |
ch.setFormatter(formatter) |
93 | 92 |
self.logger.setLevel(level) |
94 | 93 |
self.logger.addHandler(ch) |
95 | 94 |
|
96 |
def set_current_emotion(self, robot_emotion, blocking = False):
|
|
95 |
def set_current_emotion(self, robot_emotion, blocking=False):
|
|
97 | 96 |
"""set the current emotion |
98 | 97 |
:param robot_emotion: a RobotEmotion object |
99 | 98 |
:param blocking: should this call block during execution? |
... | ... | |
101 | 100 |
self.logger.debug("set_current_emotion(%s) %s" % (robot_emotion, ("BLOCKING" if blocking else "NON_BLOCKING"))) |
102 | 101 |
self.middleware.set_current_emotion(robot_emotion, blocking) |
103 | 102 |
|
104 |
def set_default_emotion(self, robot_emotion, blocking = False):
|
|
103 |
def set_default_emotion(self, robot_emotion, blocking=False):
|
|
105 | 104 |
"""set the default emotion |
106 | 105 |
:param robot_emotion: a RobotEmotion object |
107 | 106 |
:param blocking: should this call block during execution? |
... | ... | |
109 | 108 |
self.logger.debug("set_default_emotion(%s) %s" % (robot_emotion, ("BLOCKING" if blocking else "NON_BLOCKING"))) |
110 | 109 |
self.middleware.set_default_emotion(robot_emotion, blocking) |
111 | 110 |
|
112 |
def set_gaze_target(self, robot_gaze, blocking = False):
|
|
111 |
def set_gaze_target(self, robot_gaze, blocking=False):
|
|
113 | 112 |
"""set a gaze target |
114 | 113 |
:param robot_gaze: a RobotGaze object |
115 | 114 |
:param blocking: should this call block during execution? |
... | ... | |
118 | 117 |
self.logger.debug("set_gaze_target(%s) %s" % (robot_gaze, ("BLOCKING" if blocking else "NON_BLOCKING"))) |
119 | 118 |
self.middleware.set_gaze_target(robot_gaze, blocking) |
120 | 119 |
|
121 |
def set_mouth_target(self, robot_mouth, blocking = False): |
|
120 |
def set_lookat_target(self, x, y, z, blocking=False, frame_id='', roll=0.0): |
|
121 |
"""set a gaze at a Cartesian position |
|
122 |
:param x,y,z: position to look at (in eyes frame or frame_id) |
|
123 |
:param roll: side-ways motion of head |
|
124 |
:param blocking: True if this call should block until execution finished on robot |
|
125 |
""" |
|
126 |
self.logger.debug("set_lookat_target(%s) %s" % ((x,y,z), "BLOCKING" if blocking else "NON_BLOCKING")) |
|
127 |
self.middleware.set_lookat_target(x, y, z, blocking, frame_id, roll) |
|
128 |
|
|
129 |
def set_mouth_target(self, robot_mouth, blocking=False): |
|
122 | 130 |
"""set a mouth target |
123 | 131 |
:param robot_mouth: a RobotMouth object |
124 | 132 |
:param blocking: should this call block during execution? |
... | ... | |
126 | 134 |
self.logger.debug("set_mouth_target(%s) %s" % (robot_mouth, ("BLOCKING" if blocking else "NON_BLOCKING"))) |
127 | 135 |
self.middleware.set_mouth_target(robot_mouth, blocking) |
128 | 136 |
|
129 |
def set_head_animation(self, robot_animation, blocking = False):
|
|
137 |
def set_head_animation(self, robot_animation, blocking=False):
|
|
130 | 138 |
"""set a head animation |
131 | 139 |
:param robot_animation: a RobotAnimation object |
132 | 140 |
:param blocking: should this call block during execution? |
... | ... | |
134 | 142 |
self.logger.debug("set_head_animation(%s) %s" % (robot_animation, ("BLOCKING" if blocking else "NON_BLOCKING"))) |
135 | 143 |
self.middleware.set_head_animation(robot_animation, blocking) |
136 | 144 |
|
137 |
def set_speak(self, text, blocking = False):
|
|
145 |
def set_speak(self, text, blocking=False):
|
|
138 | 146 |
"""request the robot to say something using tts |
139 | 147 |
:param text: text to synthesize |
140 | 148 |
:param blocking: should this call block during execution? |
141 | 149 |
""" |
142 | 150 |
self.logger.debug("set_speak(%s) %s" % (text, ("BLOCKING" if blocking else "NON_BLOCKING"))) |
143 | 151 |
self.middleware.set_speak(text, blocking) |
144 |
|
|
145 |
#def get_gaze_target(self): |
|
146 |
# result = self.middleware.get_gaze_target() |
|
147 |
# self.logger.debug("get_gaze_target() returned %s" % (result)) |
|
148 |
# return self.middleware.get_gaze_target() |
Also available in: Unified diff