Statistics
| Branch: | Tag: | Revision:

hlrc / client / python / hlrc_client / MiddlewareROS.py @ f8fa1217

History | View | Annotate | Download (10.44 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
try:
32
        import roslib; 
33
        
34
        import rospy 
35
        import actionlib
36
        from hlrc_server.msg import *
37
    
38
except ImportError as exception:
39
        sys.stderr.write("ImportError: {}\n> HINT: try to export PYTHONPATH=$PYTHONPATH:$YOUR_PREFIX/lib/python2.7/site-packages/\n\n".format(exception))
40
        sys.exit(errno.ENOPKG)
41

    
42
class MiddlewareROS(Middleware):
43
        #default timeout to wait in case of blocking calls
44
        ROS_ACTION_CALL_TIMEOUT = 30.0
45
        
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
                        
56
        def __del__(self):
57
                """destructor
58
                """
59
                self.logger.debug("destructor of MiddlewareROS called")
60
                
61
        #######################################################################
62
        def init_middleware(self):
63
                """initialise middleware
64
                """
65
                self.logger.info("initialising ROS middleware connection on scope %s" % (self.base_scope))
66
                
67
                rospy.init_node('hlrc_client', anonymous=True)
68
                
69
                self.logger.info("creating action clients")
70
                
71
                self.logger.debug("creating speech action client")
72
                self.speech_client = actionlib.SimpleActionClient(self.base_scope + "/set/speech", speechAction)
73
                self.speech_client.wait_for_server()
74
                
75
                self.logger.debug("creating default emotion action client")
76
                self.default_emotion_client = actionlib.SimpleActionClient(self.base_scope + "/set/defaultEmotion", emotionstateAction)
77
                self.default_emotion_client.wait_for_server()
78
                
79
                self.logger.debug("creating current emotion action client")
80
                self.current_emotion_client = actionlib.SimpleActionClient(self.base_scope + "/set/currentEmotion", emotionstateAction)
81
                self.current_emotion_client.wait_for_server()
82
                
83
                self.logger.debug("creating animation action client")
84
                self.animation_client = actionlib.SimpleActionClient(self.base_scope + "/set/animation", animationAction)
85
                self.animation_client.wait_for_server()
86
                
87
                self.logger.debug("creating gazetarget action client")
88
                self.gazetarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/gaze", gazetargetAction)
89
                self.gazetarget_client.wait_for_server()
90
                
91
                self.logger.debug("creating mouthtarget action client")
92
                self.mouthtarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/mouth", mouthtargetAction)
93
                self.mouthtarget_client.wait_for_server()
94
                
95
                self.logger.info("MiddlewareROS initialised")
96
                
97

    
98
        #######################################################################
99
        def publish_emotion(self, em_type, emotion, blocking):
100
                """publish an emotion via mw
101
                :param em_type: type of emotion (RobotEmotion::TYPE_DEFAULT or RobotEmotion::TYPE_CURRENT)
102
                :param emotion: emotion to set
103
                :param blocking: True if this call should block until execution finished on robot
104
                """
105
                self.logger.debug("calling the emotion rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
106
                
107
                #create a goal to send to the action server.
108
                goal = emotionstateGoal()
109
                goal.value    = self.convert_emotiontype_to_rosval(emotion.value)
110
                goal.duration =  int(emotion.time_ms)
111
                
112
                #which client do we use?
113
                if (em_type == RobotEmotion.TYPE_DEFAULT):
114
                        client = self.default_emotion_client
115
                else:
116
                        client = self.current_emotion_client
117
                
118
                #send the goal to the server
119
                client.send_goal(goal)
120
                
121
                #wait for the server to finish 
122
                if (blocking):
123
                        timed_out = client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
124
                        if (timed_out):
125
                                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
126
                
127
        def publish_default_emotion(self, emotion, blocking):
128
                self.publish_emotion(RobotEmotion.TYPE_DEFAULT, emotion, blocking)
129
        
130
        def publish_current_emotion(self, emotion, blocking):
131
                self.publish_emotion(RobotEmotion.TYPE_CURRENT, emotion, blocking)
132
        
133
        def publish_head_animation(self, animation, blocking):
134
                """publish an head animation via mw
135
                :param animation: animation to set
136
                :param blocking: True if this call should block until execution finished on robot
137
                """
138
                self.logger.debug("calling the animation rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
139
                
140
                #create a goal to send to the action server.
141
                goal = animationGoal()
142
                goal.target = self.convert_animationtype_to_rosval(animation.value)
143
                goal.repetitions = animation.repetitions
144
                goal.duration_each =  int(animation.time_ms)
145
                goal.scale = animation.scale
146
                
147
                #send the goal to the server
148
                self.animation_client.send_goal(goal)
149
                
150
                #wait for the server to finish 
151
                if (blocking):
152
                        timed_out = self.animation_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
153
                        if (timed_out):
154
                                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
155
                
156
                self.logger.debug("animation rpc done")
157
        
158
        def publish_gaze_target(self, gaze, blocking):
159
                """publish a gaze target via mw
160
                :param gaze: gaze to set
161
                :param blocking: True if this call should block until execution finished on robot
162
                """
163
                self.logger.debug("calling the gaze rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
164
                
165
                #create a goal to send to the action server.
166
                goal = gazetargetGoal()
167
                goal.pan  = gaze.pan
168
                goal.tilt = gaze.tilt
169
                goal.roll = gaze.roll
170
                goal.vergence = gaze.vergence
171
                goal.pan_offset  = gaze.pan_offset
172
                goal.tilt_offset = gaze.tilt_offset
173
                
174
                #send the goal to the server
175
                self.gazetarget_client.send_goal(goal)
176
                
177
                #wait for the server to finish 
178
                if (blocking):
179
                        timed_out = self.gazetarget_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
180
                        if (timed_out):
181
                                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
182
                
183
                
184
                self.logger.debug("gaze rpc done")
185
        
186
        def publish_mouth_target(self, mouth, blocking):
187
                """publish a mouth target via mw
188
                :param mouth: mouth value to set
189
                :param blocking: True if this call should block until execution finished on robot
190
                """
191
                self.logger.debug("calling the mouth rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
192
                
193
                #create a goal to send to the action server.
194
                goal = mouthtargetGoal()
195
                goal.opening_left  = mouth.opening_left
196
                goal.opening_center = mouth.opening_center
197
                goal.opening_right = mouth.opening_right
198
                goal.position_left = mouth.position_left
199
                goal.position_center  = mouth.position_center
200
                goal.position_right = mouth.position_right
201
                
202
                #send the goal to the server
203
                self.mouthtarget_client.send_goal(goal)
204
                
205
                #wait for the server to finish 
206
                if (blocking):
207
                        timed_out = self.mouthtarget_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
208
                        if (timed_out):
209
                                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
210
                
211
                self.logger.debug("mouth rpc done")
212
        
213
        def publish_speech(self, text_, blocking):
214
                """publish a tts request via mw
215
                :param text_: text to synthesize and speak
216
                :param blocking: True if this call should block until execution finished on robot
217
                """
218
                self.logger.debug("calling the speech rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
219
                
220
                #create a goal to send to the action server.
221
                goal = speechGoal(text=text_)
222
                
223
                #send the goal to the server
224
                self.speech_client.send_goal(goal)
225
                
226
                #wait for the server to finish 
227
                if (blocking):
228
                        timed_out = self.speech_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
229
                        if (timed_out):
230
                                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
231
                                
232
                self.logger.debug("speech rpc done")
233
        
234
        #######################################################################
235
        # some helpers
236
        def convert_animationtype_to_rosval(self, value):
237
                """convert RobotAnimation.value to ROS animation value
238
                :param value: RobotAnimation.* id to convert to rsb id
239
                """
240
                #NOTE: this convertion is important as the actual integer values of
241
                #      thy python api and the protobuf might be different
242
                if (value == RobotAnimation.IDLE):
243
                        return animationGoal.IDLE
244
                elif (value == RobotAnimation.HEAD_NOD):
245
                        return animationGoal.HEAD_NOD
246
                elif (value == RobotAnimation.HEAD_SHAKE):
247
                        return animationGoal.HEAD_SHAKE
248
                elif (value == RobotAnimation.EYEBLINK_L):
249
                        return animationGoal.EYEBLINK_L
250
                elif (value == RobotAnimation.EYEBLINK_R):
251
                        return  animationGoal.EYEBLINK_R
252
                elif (value == RobotAnimation.EYEBLINK_BOTH):
253
                        return  animationGoal.EYEBLINK_BOTH
254
                elif (value == RobotAnimation.EYEBROWS_RAISE):
255
                        return  animationGoal.EYEBROWS_RAISE
256
                elif (value == RobotAnimation.EYEBROWS_LOWER):
257
                        return  animationGoal.EYEBROWS_LOWER
258
                else:
259
                        self.logger.error("invalid animation type %d\n" % (value))
260
                        return  animationGoal.NEUTRAL
261
                
262
        def convert_emotiontype_to_rosval(self, value):
263
                """convert RobotEmotion.value to ROS animation value
264
                :param value: RobotEmotion.* id to convert to ros id
265
                """
266
                #NOTE: this convertion is important as the actual integer values of
267
                #      thy python api and the protobuf might be different
268

    
269
                if (value == RobotEmotion.NEUTRAL):
270
                        return emotionstateGoal.NEUTRAL
271
                elif (value == RobotEmotion.HAPPY):
272
                        return emotionstateGoal.HAPPY
273
                elif (value == RobotEmotion.SAD):
274
                        return emotionstateGoal.SAD
275
                elif (value == RobotEmotion.ANGRY):
276
                        return emotionstateGoal.ANGRY
277
                elif (value == RobotEmotion.SURPRISED):
278
                        return  emotionstateGoal.SURPRISED
279
                elif (value == RobotEmotion.FEAR):
280
                        return emotionstateGoal.FEAR
281
                else:
282
                        self.logger.error("invalid emotion type %d\n" % (value))
283
                        return  emotionstateGoal.NEUTRAL