Statistics
| Branch: | Tag: | Revision:

hlrc / client / python / hlrc_client / MiddlewareROS.py @ 54cb7fdf

History | View | Annotate | Download (11.767 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 70c54617 Simon Schulz
import roslib;
32
import rospy
33 64f5c90e Simon Schulz
import actionlib
34
from hlrc_server.msg import *
35 0c286af0 Simon Schulz
36
class MiddlewareROS(Middleware):
37 3877047d Simon Schulz
    #default timeout to wait in case of blocking calls
38
    ROS_ACTION_CALL_TIMEOUT = 30.0
39
40
    #######################################################################
41
    def __init__(self, scope, loglevel=logging.WARNING):
42 70c54617 Simon Schulz
        """initialise
43
        :param scope: base scope we want to listen on
44
        """
45
        #init base settings
46
        Middleware.__init__(self,scope,loglevel)
47
        #call mw init
48
        self.init_middleware()
49
50
    def __del__(self):
51
        """destructor
52
        """
53
        self.logger.debug("destructor of MiddlewareROS called")
54
55
    #######################################################################
56
    def init_middleware(self):
57
        """initialise middleware
58
        """
59
        self.logger.info("initialising ROS middleware connection on scope %s" % (self.base_scope))
60
61
        rospy.init_node('hlrc_client', anonymous=True)
62
63
        self.logger.info("creating action clients")
64
65
        self.logger.debug("creating speech action client")
66
        self.speech_client = actionlib.SimpleActionClient(self.base_scope + "/set/speech", speechAction)
67
        self.speech_client.wait_for_server()
68
69
        self.logger.debug("creating default emotion action client")
70
        self.default_emotion_client = actionlib.SimpleActionClient(self.base_scope + "/set/defaultEmotion", emotionstateAction)
71
        self.default_emotion_client.wait_for_server()
72
73
        self.logger.debug("creating current emotion action client")
74
        self.current_emotion_client = actionlib.SimpleActionClient(self.base_scope + "/set/currentEmotion", emotionstateAction)
75
        self.current_emotion_client.wait_for_server()
76
77
        self.logger.debug("creating animation action client")
78
        self.animation_client = actionlib.SimpleActionClient(self.base_scope + "/set/animation", animationAction)
79
        self.animation_client.wait_for_server()
80
81
        self.logger.debug("creating gazetarget action client")
82
        self.gazetarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/gaze", gazetargetAction)
83
        self.gazetarget_client.wait_for_server()
84
85
        self.logger.debug("creating mouthtarget action client")
86
        self.mouthtarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/mouth", mouthtargetAction)
87
        self.mouthtarget_client.wait_for_server()
88
89
        self.logger.info("MiddlewareROS initialised")
90
91 02fc76ae Simon Schulz
    #######################################################################
92
    def is_running(self):
93
        return not rospy.is_shutdown()
94 70c54617 Simon Schulz
95
    #######################################################################
96
    def publish_emotion(self, em_type, emotion, blocking):
97
        """publish an emotion via mw
98
        :param em_type: type of emotion (RobotEmotion::TYPE_DEFAULT or RobotEmotion::TYPE_CURRENT)
99
        :param emotion: emotion to set
100
        :param blocking: True if this call should block until execution finished on robot
101
        """
102
        self.logger.debug("calling the emotion rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
103
104
        #create a goal to send to the action server.
105
        goal = emotionstateGoal()
106
        goal.value    = self.convert_emotiontype_to_rosval(emotion.value)
107
        goal.duration =  int(emotion.time_ms)
108
109
        #which client do we use?
110
        if (em_type == RobotEmotion.TYPE_DEFAULT):
111
            client = self.default_emotion_client
112
        else:
113
            client = self.current_emotion_client
114
115
        #send the goal to the server
116
        client.send_goal(goal)
117
118
        #wait for the server to finish
119
        if (blocking):
120
            timed_out = client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
121
            if (timed_out):
122
                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
123
124
    def publish_default_emotion(self, emotion, blocking):
125
        self.publish_emotion(RobotEmotion.TYPE_DEFAULT, emotion, blocking)
126
127
    def publish_current_emotion(self, emotion, blocking):
128
        self.publish_emotion(RobotEmotion.TYPE_CURRENT, emotion, blocking)
129
130
    def publish_head_animation(self, animation, blocking):
131
        """publish an head animation via mw
132
        :param animation: animation to set
133
        :param blocking: True if this call should block until execution finished on robot
134
        """
135
        self.logger.debug("calling the animation rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
136
137
        #create a goal to send to the action server.
138
        goal = animationGoal()
139
        goal.target = self.convert_animationtype_to_rosval(animation.value)
140
        goal.repetitions = animation.repetitions
141
        goal.duration_each =  int(animation.time_ms)
142
        goal.scale = animation.scale
143
144
        #send the goal to the server
145
        self.animation_client.send_goal(goal)
146
147
        #wait for the server to finish
148
        if (blocking):
149
            timed_out = self.animation_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
150
            if (timed_out):
151
                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
152
153
        self.logger.debug("animation rpc done")
154
155
    def publish_gaze_target(self, gaze, blocking):
156
        """publish a gaze target via mw
157
        :param gaze: gaze to set
158
        :param blocking: True if this call should block until execution finished on robot
159
        """
160
        self.logger.debug("calling the gaze rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
161
162
        #create a goal to send to the action server.
163
        goal = gazetargetGoal()
164
        goal.pan  = gaze.pan
165
        goal.tilt = gaze.tilt
166
        goal.roll = gaze.roll
167
        goal.vergence = gaze.vergence
168
        goal.pan_offset  = gaze.pan_offset
169
        goal.tilt_offset = gaze.tilt_offset
170
171
        #type
172
        if (gaze.gaze_type == RobotGaze.GAZETARGET_ABSOLUTE):
173
            goal.gaze_type = gazetargetGoal.GAZETARGET_ABSOLUTE
174
        else:
175
            goal.gaze_type = gazetargetGoal.GAZETARGET_RELATIVE
176
177 0e7e9a0e Simon Schulz
        goal.gaze_timestamp = rospy.Time.from_sec(gaze.timestamp)
178 70c54617 Simon Schulz
179
        #send the goal to the server
180
        self.gazetarget_client.send_goal(goal)
181
182
        #wait for the server to finish
183
        if (blocking):
184
            timed_out = self.gazetarget_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
185
            if (timed_out):
186
                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
187
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 a goal to send to the action server.
199
        goal = mouthtargetGoal()
200
        goal.opening_left  = mouth.opening_left
201
        goal.opening_center = mouth.opening_center
202
        goal.opening_right = mouth.opening_right
203
        goal.position_left = mouth.position_left
204
        goal.position_center  = mouth.position_center
205
        goal.position_right = mouth.position_right
206
207
        #send the goal to the server
208
        self.mouthtarget_client.send_goal(goal)
209
210
        #wait for the server to finish
211
        if (blocking):
212
            timed_out = self.mouthtarget_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
213
            if (timed_out):
214
                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
215
216
        self.logger.debug("mouth rpc done")
217
218
    def publish_speech(self, text_, blocking):
219
        """publish a tts request via mw
220
        :param text_: text to synthesize and speak
221
        :param blocking: True if this call should block until execution finished on robot
222
        """
223
        self.logger.debug("calling the speech rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
224
225
        #create a goal to send to the action server.
226
        goal = speechGoal(text=text_)
227
228
        #send the goal to the server
229
        self.speech_client.send_goal(goal)
230
231
        #wait for the server to finish
232
        if (blocking):
233
            timed_out = self.speech_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
234
            if (timed_out):
235
                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
236
237
        self.logger.debug("speech rpc done")
238
239
    #######################################################################
240
    # some helpers
241
    def convert_animationtype_to_rosval(self, value):
242
        """convert RobotAnimation.value to ROS animation value
243
        :param value: RobotAnimation.* id to convert to rsb id
244
        """
245
        #NOTE: this convertion is important as the actual integer values of
246
        #      thy python api and the protobuf might be different
247
        if (value == RobotAnimation.IDLE):
248
            return animationGoal.IDLE
249
        elif (value == RobotAnimation.HEAD_NOD):
250
            return animationGoal.HEAD_NOD
251
        elif (value == RobotAnimation.HEAD_SHAKE):
252
            return animationGoal.HEAD_SHAKE
253
        elif (value == RobotAnimation.EYEBLINK_L):
254
            return animationGoal.EYEBLINK_L
255
        elif (value == RobotAnimation.EYEBLINK_R):
256
            return  animationGoal.EYEBLINK_R
257
        elif (value == RobotAnimation.EYEBLINK_BOTH):
258
            return  animationGoal.EYEBLINK_BOTH
259
        elif (value == RobotAnimation.EYEBROWS_RAISE):
260
            return  animationGoal.EYEBROWS_RAISE
261
        elif (value == RobotAnimation.EYEBROWS_LOWER):
262
            return  animationGoal.EYEBROWS_LOWER
263
        else:
264
            self.logger.error("invalid animation type %d\n" % (value))
265
            return  animationGoal.NEUTRAL
266
267
    def convert_emotiontype_to_rosval(self, value):
268
        """convert RobotEmotion.value to ROS animation value
269
        :param value: RobotEmotion.* id to convert to ros 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 emotionstateGoal.NEUTRAL
276
        elif (value == RobotEmotion.HAPPY):
277
            return emotionstateGoal.HAPPY
278
        elif (value == RobotEmotion.SAD):
279
            return emotionstateGoal.SAD
280
        elif (value == RobotEmotion.ANGRY):
281
            return emotionstateGoal.ANGRY
282
        elif (value == RobotEmotion.SURPRISED):
283
            return  emotionstateGoal.SURPRISED
284
        elif (value == RobotEmotion.FEAR):
285
            return emotionstateGoal.FEAR
286
        else:
287
            self.logger.error("invalid emotion type %d\n" % (value))
288
            return  emotionstateGoal.NEUTRAL