hlrc / client / python / hlrc_client / MiddlewareRSB.py @ f4b07d1e
History | View | Annotate | Download (10.107 KB)
1 | 0c286af0 | Simon Schulz | """
|
---|---|---|---|
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 | try:
|
||
32 | import rsb |
||
33 | import rsb.converter |
||
34 | import rst |
||
35 | import rstsandbox |
||
36 | from rst.robot.EmotionState_pb2 import EmotionState |
||
37 | from rst.robot.Animation_pb2 import Animation |
||
38 | from rst.robot.GazeTarget_pb2 import GazeTarget |
||
39 | from rst.robot.MouthTarget_pb2 import MouthTarget |
||
40 | |||
41 | except ImportError as exception: |
||
42 | sys.stderr.write("ImportError: {}\n> HINT: try to export PYTHONPATH=$PYTHONPATH:$YOUR_PREFIX/lib/python2.7/site-packages/\n\n".format(exception))
|
||
43 | sys.exit(errno.ENOPKG) |
||
44 | |||
45 | class MiddlewareRSB(Middleware): |
||
46 | #######################################################################
|
||
47 | def __init__(self, scope, loglevel=logging.WARNING): |
||
48 | """initialise
|
||
49 | :param scope: base scope we want to listen on
|
||
50 | """
|
||
51 | #init base settings
|
||
52 | Middleware.__init__(self,scope,loglevel)
|
||
53 | #call mw init
|
||
54 | self.init_middleware()
|
||
55 | f8fa1217 | Simon Schulz | |
56 | def __del__(self): |
||
57 | """destructor
|
||
58 | """
|
||
59 | self.logger.debug("destructor of MiddlewareROS called") |
||
60 | |||
61 | 0c286af0 | Simon Schulz | #######################################################################
|
62 | def init_middleware(self): |
||
63 | """initialise middleware
|
||
64 | """
|
||
65 | #mute rsb logging:
|
||
66 | logging.getLogger("rsb").setLevel(logging.ERROR)
|
||
67 | |||
68 | #initialise RSB stuff
|
||
69 | self.logger.info("initialising RSB middleware connection on scope %s, registering rst converters..." % (self.base_scope)) |
||
70 | |||
71 | self.emotionstate_converter = rsb.converter.ProtocolBufferConverter(messageClass = EmotionState)
|
||
72 | rsb.converter.registerGlobalConverter(self.emotionstate_converter)
|
||
73 | |||
74 | self.animation_converter = rsb.converter.ProtocolBufferConverter(messageClass = Animation)
|
||
75 | rsb.converter.registerGlobalConverter(self.animation_converter)
|
||
76 | |||
77 | self.gaze_converter = rsb.converter.ProtocolBufferConverter(messageClass = GazeTarget)
|
||
78 | rsb.converter.registerGlobalConverter(self.gaze_converter)
|
||
79 | |||
80 | self.mouth_converter = rsb.converter.ProtocolBufferConverter(messageClass = MouthTarget)
|
||
81 | rsb.converter.registerGlobalConverter(self.mouth_converter)
|
||
82 | |||
83 | try:
|
||
84 | self.server = rsb.createRemoteServer(self.base_scope + '/set') |
||
85 | except ValueError: |
||
86 | self.logger.error("ERROR: invalid scope given. server deactivated") |
||
87 | self.server.deactivate()
|
||
88 | sys.exit(errno.EINVAL) |
||
89 | |||
90 | #######################################################################
|
||
91 | def publish_emotion(self, em_type, emotion, blocking): |
||
92 | """publish an emotion via mw
|
||
93 | :param em_type: type of emotion (RobotEmotion::TYPE_DEFAULT or RobotEmotion::TYPE_CURRENT)
|
||
94 | :param emotion: emotion to set
|
||
95 | :param blocking: True if this call should block until execution finished on robot
|
||
96 | """
|
||
97 | |||
98 | #create emotion & fill it with values:
|
||
99 | rsb_em = EmotionState() |
||
100 | |||
101 | #set value
|
||
102 | rsb_em.value = self.convert_emotiontype_to_rsbval(emotion.value)
|
||
103 | |||
104 | #set duration
|
||
105 | rsb_em.duration = int(emotion.time_ms)
|
||
106 | |||
107 | with rsb.createRemoteServer(self.base_scope + '/set') as server: |
||
108 | self.logger.debug("calling the emotion rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
||
109 | |||
110 | if (blocking):
|
||
111 | #blocking rpc call:
|
||
112 | if (em_type == RobotEmotion.TYPE_DEFAULT):
|
||
113 | result = server.defaultEmotion(rsb_em) |
||
114 | else:
|
||
115 | result = server.currentEmotion(rsb_em) |
||
116 | |||
117 | self.logger.debug("server reply: '%s'" % result) |
||
118 | else:
|
||
119 | if (em_type == RobotEmotion.TYPE_DEFAULT):
|
||
120 | future = server.defaultEmotion.async(rsb_em) |
||
121 | else:
|
||
122 | future = server.currentEmotion.async(rsb_em) |
||
123 | |||
124 | #we could block here for a incoming result with a timeout in s
|
||
125 | #print '> server reply: "%s"' % future.get(timeout = 10);
|
||
126 | self.logger.debug("emotion rpc done") |
||
127 | |||
128 | def publish_head_animation(self, animation, blocking): |
||
129 | """publish an head animation via mw
|
||
130 | :param animation: animation to set
|
||
131 | :param blocking: True if this call should block until execution finished on robot
|
||
132 | """
|
||
133 | |||
134 | self.logger.debug("calling the animation rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
||
135 | |||
136 | #create animation & fill it with values:
|
||
137 | rsb_ani = Animation() |
||
138 | |||
139 | #select ani
|
||
140 | rsb_ani.target = self.convert_animationtype_to_rsbval(animation.value)
|
||
141 | rsb_ani.repetitions = animation.repetitions |
||
142 | rsb_ani.duration_each = animation.time_ms |
||
143 | rsb_ani.scale = animation.scale |
||
144 | |||
145 | if (blocking):
|
||
146 | #blocking:
|
||
147 | result = self.server.animation(rsb_ani)
|
||
148 | self.logger.debug("server reply: '%s'" % result) |
||
149 | else:
|
||
150 | future = self.server.animation.async(rsb_ani)
|
||
151 | #we can block here for a incoming result with a timeout in s
|
||
152 | #print '> server reply: "%s"' % future.get(timeout = 10);
|
||
153 | |||
154 | self.logger.debug("animation rpc done") |
||
155 | |||
156 | def publish_default_emotion(self, emotion, blocking): |
||
157 | self.publish_emotion(RobotEmotion.TYPE_DEFAULT, emotion, blocking)
|
||
158 | |||
159 | def publish_current_emotion(self, emotion, blocking): |
||
160 | self.publish_emotion(RobotEmotion.TYPE_CURRENT, emotion, blocking)
|
||
161 | |||
162 | def publish_gaze_target(self, gaze, blocking): |
||
163 | """publish a gaze target via mw
|
||
164 | :param gaze: gaze to set
|
||
165 | :param blocking: True if this call should block until execution finished on robot
|
||
166 | """
|
||
167 | self.logger.debug("calling the gaze rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
||
168 | |||
169 | #create gaze target & fill it with values:
|
||
170 | rsb_gaze = GazeTarget() |
||
171 | |||
172 | #fill proto
|
||
173 | rsb_gaze.pan = gaze.pan |
||
174 | rsb_gaze.tilt = gaze.tilt |
||
175 | rsb_gaze.roll = gaze.roll |
||
176 | rsb_gaze.vergence = gaze.vergence |
||
177 | rsb_gaze.pan_offset = gaze.pan_offset |
||
178 | rsb_gaze.tilt_offset = gaze.tilt_offset |
||
179 | |||
180 | if (blocking):
|
||
181 | #blocking:
|
||
182 | result = self.server.gaze(rsb_gaze)
|
||
183 | self.logger.debug("server reply: '%s'" % result) |
||
184 | else:
|
||
185 | future = self.server.gaze.async(rsb_gaze)
|
||
186 | #we can block here for a incoming result with a timeout in s
|
||
187 | #print '> server reply: "%s"' % future.get(timeout = 10);
|
||
188 | |||
189 | self.logger.debug("gaze rpc done") |
||
190 | |||
191 | def publish_mouth_target(self, mouth, blocking): |
||
192 | """publish a mouth target via mw
|
||
193 | :param mouth: mouth value to set
|
||
194 | :param blocking: True if this call should block until execution finished on robot
|
||
195 | """
|
||
196 | self.logger.debug("calling the mouth rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
||
197 | |||
198 | #create mouth state & fill it with values:
|
||
199 | rsb_mouth = MouthTarget() |
||
200 | |||
201 | #fill proto
|
||
202 | rsb_mouth.opening_left = mouth.opening_left |
||
203 | rsb_mouth.opening_center = mouth.opening_center |
||
204 | rsb_mouth.opening_right = mouth.opening_right |
||
205 | rsb_mouth.position_left = mouth.position_left |
||
206 | rsb_mouth.position_center = mouth.position_center |
||
207 | rsb_mouth.position_right = mouth.position_right |
||
208 | |||
209 | if (blocking):
|
||
210 | #blocking:
|
||
211 | result = self.server.mouth(rsb_mouth)
|
||
212 | self.logger.debug("server reply: '%s'" % result) |
||
213 | else:
|
||
214 | future = self.server.mouth.async(rsb_mouth)
|
||
215 | #we can block here for a incoming result with a timeout in s
|
||
216 | #print '> server reply: "%s"' % future.get(timeout = 10);
|
||
217 | |||
218 | self.logger.debug("mouth rpc done") |
||
219 | |||
220 | def publish_speech(self, text, blocking): |
||
221 | """publish a tts request via mw
|
||
222 | :param text: text to synthesize and speak
|
||
223 | :param blocking: True if this call should block until execution finished on robot
|
||
224 | """
|
||
225 | self.logger.debug("calling the speech rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
||
226 | |||
227 | if (blocking):
|
||
228 | #blocking:
|
||
229 | result = self.server.speech(text)
|
||
230 | self.logger.debug("server reply: '%s'" % result) |
||
231 | else:
|
||
232 | future = self.server.speech.async(text)
|
||
233 | #we can block here for a incoming result with a timeout in s
|
||
234 | #print '> server reply: "%s"' % future.get(timeout = 10);
|
||
235 | |||
236 | self.logger.debug("speech rpc done") |
||
237 | |||
238 | #######################################################################
|
||
239 | # some helpers
|
||
240 | def convert_animationtype_to_rsbval(self, value): |
||
241 | """convert RobotAnimation.value to RSB animation value
|
||
242 | :param value: RobotAnimation.* id to convert to rsb id
|
||
243 | """
|
||
244 | #NOTE: this convertion is important as the actual integer values of
|
||
245 | # thy python api and the protobuf might be different
|
||
246 | |||
247 | if (value == RobotAnimation.IDLE):
|
||
248 | return Animation().IDLE
|
||
249 | elif (value == RobotAnimation.HEAD_NOD):
|
||
250 | return Animation().HEAD_NOD
|
||
251 | elif (value == RobotAnimation.HEAD_SHAKE):
|
||
252 | return Animation().HEAD_SHAKE
|
||
253 | elif (value == RobotAnimation.EYEBLINK_L):
|
||
254 | return Animation().EYEBLINK_L
|
||
255 | elif (value == RobotAnimation.EYEBLINK_R):
|
||
256 | return Animation().EYEBLINK_R
|
||
257 | elif (value == RobotAnimation.EYEBLINK_BOTH):
|
||
258 | return Animation().EYEBLINK_BOTH
|
||
259 | elif (value == RobotAnimation.EYEBROWS_RAISE):
|
||
260 | return Animation().EYEBROWS_RAISE
|
||
261 | elif (value == RobotAnimation.EYEBROWS_LOWER):
|
||
262 | return Animation().EYEBROWS_LOWER
|
||
263 | else:
|
||
264 | self.logger.error("invalid animation type %d\n" % (value)) |
||
265 | return Animation().NEUTRAL
|
||
266 | |||
267 | def convert_emotiontype_to_rsbval(self, value): |
||
268 | """convert RobotEmotion.value to RSB animation value
|
||
269 | :param value: RobotEmotion.* id to convert to rsb id
|
||
270 | """
|
||
271 | #NOTE: this convertion is important as the actual integer values of
|
||
272 | # thy python api and the protobuf might be different
|
||
273 | |||
274 | if (value == RobotEmotion.NEUTRAL):
|
||
275 | return EmotionState().NEUTRAL
|
||
276 | elif (value == RobotEmotion.HAPPY):
|
||
277 | return EmotionState().HAPPY
|
||
278 | elif (value == RobotEmotion.SAD):
|
||
279 | return EmotionState().SAD
|
||
280 | elif (value == RobotEmotion.ANGRY):
|
||
281 | return EmotionState().ANGRY
|
||
282 | elif (value == RobotEmotion.SURPRISED):
|
||
283 | return EmotionState().SURPRISED
|
||
284 | elif (value == RobotEmotion.FEAR):
|
||
285 | return EmotionState().FEAR
|
||
286 | else:
|
||
287 | self.logger.error("invalid emotion type %d\n" % (value)) |
||
288 | return EmotionState().NEUTRAL |