hlrc / client / python / hlrc_client / MiddlewareROS.py @ 2cf3c285
History | View | Annotate | Download (14.083 KB)
1 |
"""
|
---|---|
2 |
This file is part of hlrc
|
3 |
|
4 |
Copyright(c) sschulz <AT> techfak.uni-bielefeld.de
|
5 |
http://opensource.cit-ec.de/projects/hlrc
|
6 |
|
7 |
This file may be licensed under the terms of the
|
8 |
GNU General Public License Version 3 (the ``GPL''),
|
9 |
or (at your option) any later version.
|
10 |
|
11 |
Software distributed under the License is distributed
|
12 |
on an ``AS IS'' basis, WITHOUT WARRANTY OF ANY KIND, either
|
13 |
express or implied. See the GPL for the specific language
|
14 |
governing rights and limitations.
|
15 |
|
16 |
You should have received a copy of the GPL along with this
|
17 |
program. If not, go to http://www.gnu.org/licenses/gpl.html
|
18 |
or write to the Free Software Foundation, Inc.,
|
19 |
51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
|
20 |
|
21 |
The development of this software was supported by the
|
22 |
Excellence Cluster EXC 277 Cognitive Interaction Technology.
|
23 |
The Excellence Cluster EXC 277 is a grant of the Deutsche
|
24 |
Forschungsgemeinschaft (DFG) in the context of the German
|
25 |
Excellence Initiative.
|
26 |
"""
|
27 |
|
28 |
from Middleware import * |
29 |
import errno |
30 |
|
31 |
import rospy |
32 |
import actionlib |
33 |
from hlrc_server.msg import * |
34 |
from geometry_msgs.msg import Point |
35 |
from actionlib_msgs.msg import GoalStatus |
36 |
|
37 |
class MiddlewareROS(Middleware): |
38 |
#default timeout to wait in case of blocking calls
|
39 |
ROS_ACTION_CALL_TIMEOUT = 30.0
|
40 |
|
41 |
#######################################################################
|
42 |
def __init__(self, scope, loglevel=logging.WARNING): |
43 |
"""initialise
|
44 |
:param scope: base scope we want to listen on
|
45 |
"""
|
46 |
#init base settings
|
47 |
Middleware.__init__(self,scope,loglevel)
|
48 |
#call mw init
|
49 |
self.init_middleware()
|
50 |
|
51 |
def __del__(self): |
52 |
"""destructor
|
53 |
"""
|
54 |
self.logger.debug("destructor of MiddlewareROS called") |
55 |
|
56 |
#######################################################################
|
57 |
def init_middleware(self): |
58 |
"""initialise middleware
|
59 |
"""
|
60 |
self.logger.info("initialising ROS middleware connection on scope %s" % (self.base_scope)) |
61 |
|
62 |
try:
|
63 |
rospy.init_node('hlrc_client', anonymous=True) |
64 |
except rospy.exceptions.ROSException as e: |
65 |
print e
|
66 |
|
67 |
self.logger.info("creating action clients") |
68 |
|
69 |
self.logger.debug("creating speech action client") |
70 |
self.speech_client = actionlib.SimpleActionClient(self.base_scope + "/set/speech", speechAction) |
71 |
self.speech_client.wait_for_server()
|
72 |
|
73 |
self.logger.debug("creating default emotion action client") |
74 |
self.default_emotion_client = actionlib.SimpleActionClient(self.base_scope + "/set/defaultEmotion", emotionstateAction) |
75 |
self.default_emotion_client.wait_for_server()
|
76 |
|
77 |
self.logger.debug("creating current emotion action client") |
78 |
self.current_emotion_client = actionlib.SimpleActionClient(self.base_scope + "/set/currentEmotion", emotionstateAction) |
79 |
self.current_emotion_client.wait_for_server()
|
80 |
|
81 |
self.logger.debug("creating animation action client") |
82 |
self.animation_client = actionlib.SimpleActionClient(self.base_scope + "/set/animation", animationAction) |
83 |
self.animation_client.wait_for_server()
|
84 |
|
85 |
self.logger.debug("creating gazetarget action client") |
86 |
self.gazetarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/gaze", gazetargetAction) |
87 |
self.gazetarget_client.wait_for_server()
|
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 |
|
93 |
self.logger.debug("creating mouthtarget action client") |
94 |
self.mouthtarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/mouth", mouthtargetAction) |
95 |
self.mouthtarget_client.wait_for_server()
|
96 |
|
97 |
self.logger.info("MiddlewareROS initialised") |
98 |
|
99 |
#######################################################################
|
100 |
def is_running(self): |
101 |
return not rospy.is_shutdown() |
102 |
|
103 |
#######################################################################
|
104 |
def publish_emotion(self, em_type, emotion, blocking): |
105 |
"""publish an emotion via mw
|
106 |
:param em_type: type of emotion (RobotEmotion::TYPE_DEFAULT or RobotEmotion::TYPE_CURRENT)
|
107 |
:param emotion: emotion to set
|
108 |
:param blocking: True if this call should block until execution finished on robot
|
109 |
"""
|
110 |
self.logger.debug("calling the emotion rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
111 |
|
112 |
#create a goal to send to the action server.
|
113 |
goal = emotionstateGoal() |
114 |
goal.value = self.convert_emotiontype_to_rosval(emotion.value)
|
115 |
goal.duration = int(emotion.time_ms)
|
116 |
|
117 |
#which client do we use?
|
118 |
if (em_type == RobotEmotion.TYPE_DEFAULT):
|
119 |
client = self.default_emotion_client
|
120 |
else:
|
121 |
client = self.current_emotion_client
|
122 |
|
123 |
#send the goal to the server
|
124 |
if (blocking):
|
125 |
#send and wait:
|
126 |
state = client.send_goal_and_wait(goal, execute_timeout = rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT)) |
127 |
if (state != GoalStatus.SUCCEEDED):
|
128 |
self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name)) |
129 |
else:
|
130 |
#non blocking, fire & forget
|
131 |
client.send_goal(goal) |
132 |
|
133 |
self.logger.debug("emotion rpc done") |
134 |
|
135 |
def publish_default_emotion(self, emotion, blocking): |
136 |
self.publish_emotion(RobotEmotion.TYPE_DEFAULT, emotion, blocking)
|
137 |
|
138 |
def publish_current_emotion(self, emotion, blocking): |
139 |
self.publish_emotion(RobotEmotion.TYPE_CURRENT, emotion, blocking)
|
140 |
|
141 |
def publish_head_animation(self, animation, blocking): |
142 |
"""publish an head animation via mw
|
143 |
:param animation: animation to set
|
144 |
:param blocking: True if this call should block until execution finished on robot
|
145 |
"""
|
146 |
self.logger.debug("calling the animation rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
147 |
|
148 |
#create a goal to send to the action server.
|
149 |
goal = animationGoal() |
150 |
goal.target = self.convert_animationtype_to_rosval(animation.value)
|
151 |
goal.repetitions = animation.repetitions |
152 |
goal.duration_each = int(animation.time_ms)
|
153 |
goal.scale = animation.scale |
154 |
|
155 |
#send the goal to the server
|
156 |
if (blocking):
|
157 |
#send and wait:
|
158 |
state = self.animation_client.send_goal_and_wait(goal, execute_timeout = rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
|
159 |
if (state != GoalStatus.SUCCEEDED):
|
160 |
self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name)) |
161 |
else:
|
162 |
#non blocking, fire & forget
|
163 |
self.animation_client.send_goal(goal)
|
164 |
|
165 |
self.logger.debug("animation rpc done") |
166 |
|
167 |
def publish_gaze_target(self, gaze, blocking): |
168 |
"""publish a gaze target via mw
|
169 |
:param gaze: gaze to set
|
170 |
:param blocking: True if this call should block until execution finished on robot
|
171 |
"""
|
172 |
self.logger.debug("calling the gaze rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
173 |
|
174 |
#create a goal to send to the action server.
|
175 |
goal = gazetargetGoal() |
176 |
goal.pan = gaze.pan |
177 |
goal.tilt = gaze.tilt |
178 |
goal.roll = gaze.roll |
179 |
goal.vergence = gaze.vergence |
180 |
goal.pan_offset = gaze.pan_offset |
181 |
goal.tilt_offset = gaze.tilt_offset |
182 |
|
183 |
#type
|
184 |
if (gaze.gaze_type == RobotGaze.GAZETARGET_ABSOLUTE):
|
185 |
goal.gaze_type = gazetargetGoal.GAZETARGET_ABSOLUTE |
186 |
else:
|
187 |
goal.gaze_type = gazetargetGoal.GAZETARGET_RELATIVE |
188 |
|
189 |
goal.gaze_timestamp = rospy.Time.from_sec(gaze.gaze_timestamp.to_seconds()) |
190 |
|
191 |
#send the goal to the server
|
192 |
if (blocking):
|
193 |
#send and wait:
|
194 |
state = self.gazetarget_client.send_goal_and_wait(goal, execute_timeout = rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
|
195 |
if (state != GoalStatus.SUCCEEDED):
|
196 |
self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name)) |
197 |
else:
|
198 |
#non blocking, fire & forget
|
199 |
self.gazetarget_client.send_goal(goal)
|
200 |
|
201 |
self.logger.debug("gaze rpc done") |
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 |
|
235 |
def publish_mouth_target(self, mouth, blocking): |
236 |
"""publish a mouth target via mw
|
237 |
:param mouth: mouth value to set
|
238 |
:param blocking: True if this call should block until execution finished on robot
|
239 |
"""
|
240 |
self.logger.debug("calling the mouth rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
241 |
|
242 |
#create a goal to send to the action server.
|
243 |
goal = mouthtargetGoal() |
244 |
goal.opening_left = mouth.opening_left |
245 |
goal.opening_center = mouth.opening_center |
246 |
goal.opening_right = mouth.opening_right |
247 |
goal.position_left = mouth.position_left |
248 |
goal.position_center = mouth.position_center |
249 |
goal.position_right = mouth.position_right |
250 |
|
251 |
#send the goal to the server
|
252 |
if (blocking):
|
253 |
#send and wait:
|
254 |
state = self.mouthtarget_client.send_goal_and_wait(goal, execute_timeout = rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
|
255 |
if (state != GoalStatus.SUCCEEDED):
|
256 |
self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name)) |
257 |
else:
|
258 |
#non blocking, fire & forget
|
259 |
self.mouthtarget_client.send_goal(goal)
|
260 |
|
261 |
self.logger.debug("mouth rpc done") |
262 |
|
263 |
def publish_speech(self, text_, blocking): |
264 |
"""publish a tts request via mw
|
265 |
:param text_: text to synthesize and speak
|
266 |
:param blocking: True if this call should block until execution finished on robot
|
267 |
"""
|
268 |
self.logger.debug("calling the speech rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
269 |
|
270 |
#create a goal to send to the action server.
|
271 |
goal = speechGoal(text=text_) |
272 |
|
273 |
#send the goal to the server
|
274 |
if (blocking):
|
275 |
#send and wait:
|
276 |
state = self.speech_client.send_goal_and_wait(goal, execute_timeout = rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
|
277 |
if (state != GoalStatus.SUCCEEDED):
|
278 |
self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name)) |
279 |
else:
|
280 |
#non blocking, fire & forget
|
281 |
self.speech_client.send_goal(goal)
|
282 |
|
283 |
self.logger.debug("speech rpc done") |
284 |
|
285 |
#######################################################################
|
286 |
# some helpers
|
287 |
def convert_animationtype_to_rosval(self, value): |
288 |
"""convert RobotAnimation.value to ROS animation value
|
289 |
:param value: RobotAnimation.* id to convert to rsb id
|
290 |
"""
|
291 |
#NOTE: this convertion is important as the actual integer values of
|
292 |
# thy python api and the protobuf might be different
|
293 |
if (value == RobotAnimation.IDLE):
|
294 |
return animationGoal.IDLE
|
295 |
elif (value == RobotAnimation.HEAD_NOD):
|
296 |
return animationGoal.HEAD_NOD
|
297 |
elif (value == RobotAnimation.HEAD_SHAKE):
|
298 |
return animationGoal.HEAD_SHAKE
|
299 |
elif (value == RobotAnimation.EYEBLINK_L):
|
300 |
return animationGoal.EYEBLINK_L
|
301 |
elif (value == RobotAnimation.EYEBLINK_R):
|
302 |
return animationGoal.EYEBLINK_R
|
303 |
elif (value == RobotAnimation.EYEBLINK_BOTH):
|
304 |
return animationGoal.EYEBLINK_BOTH
|
305 |
elif (value == RobotAnimation.EYEBROWS_RAISE):
|
306 |
return animationGoal.EYEBROWS_RAISE
|
307 |
elif (value == RobotAnimation.EYEBROWS_LOWER):
|
308 |
return animationGoal.EYEBROWS_LOWER
|
309 |
else:
|
310 |
self.logger.error("invalid animation type %d\n" % (value)) |
311 |
return animationGoal.NEUTRAL
|
312 |
|
313 |
def convert_emotiontype_to_rosval(self, value): |
314 |
"""convert RobotEmotion.value to ROS animation value
|
315 |
:param value: RobotEmotion.* id to convert to ros id
|
316 |
"""
|
317 |
#NOTE: this convertion is important as the actual integer values of
|
318 |
# thy python api and the protobuf might be different
|
319 |
|
320 |
if (value == RobotEmotion.NEUTRAL):
|
321 |
return emotionstateGoal.NEUTRAL
|
322 |
elif (value == RobotEmotion.HAPPY):
|
323 |
return emotionstateGoal.HAPPY
|
324 |
elif (value == RobotEmotion.SAD):
|
325 |
return emotionstateGoal.SAD
|
326 |
elif (value == RobotEmotion.ANGRY):
|
327 |
return emotionstateGoal.ANGRY
|
328 |
elif (value == RobotEmotion.SURPRISED):
|
329 |
return emotionstateGoal.SURPRISED
|
330 |
elif (value == RobotEmotion.FEAR):
|
331 |
return emotionstateGoal.FEAR
|
332 |
else:
|
333 |
self.logger.error("invalid emotion type %d\n" % (value)) |
334 |
return emotionstateGoal.NEUTRAL
|