Statistics
| Branch: | Tag: | Revision:

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

History | View | Annotate | Download (11.624 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 roslib;
32
import rospy
33
import actionlib
34
from hlrc_server.msg import *
35

    
36
class MiddlewareROS(Middleware):
37
    #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
        """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

    
92
    #######################################################################
93
    def publish_emotion(self, em_type, emotion, blocking):
94
        """publish an emotion via mw
95
        :param em_type: type of emotion (RobotEmotion::TYPE_DEFAULT or RobotEmotion::TYPE_CURRENT)
96
        :param emotion: emotion to set
97
        :param blocking: True if this call should block until execution finished on robot
98
        """
99
        self.logger.debug("calling the emotion rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
100

    
101
        #create a goal to send to the action server.
102
        goal = emotionstateGoal()
103
        goal.value    = self.convert_emotiontype_to_rosval(emotion.value)
104
        goal.duration =  int(emotion.time_ms)
105

    
106
        #which client do we use?
107
        if (em_type == RobotEmotion.TYPE_DEFAULT):
108
            client = self.default_emotion_client
109
        else:
110
            client = self.current_emotion_client
111

    
112
        #send the goal to the server
113
        client.send_goal(goal)
114

    
115
        #wait for the server to finish
116
        if (blocking):
117
            timed_out = client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
118
            if (timed_out):
119
                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
120

    
121
    def publish_default_emotion(self, emotion, blocking):
122
        self.publish_emotion(RobotEmotion.TYPE_DEFAULT, emotion, blocking)
123

    
124
    def publish_current_emotion(self, emotion, blocking):
125
        self.publish_emotion(RobotEmotion.TYPE_CURRENT, emotion, blocking)
126

    
127
    def publish_head_animation(self, animation, blocking):
128
        """publish an head animation via mw
129
        :param animation: animation to set
130
        :param blocking: True if this call should block until execution finished on robot
131
        """
132
        self.logger.debug("calling the animation rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
133

    
134
        #create a goal to send to the action server.
135
        goal = animationGoal()
136
        goal.target = self.convert_animationtype_to_rosval(animation.value)
137
        goal.repetitions = animation.repetitions
138
        goal.duration_each =  int(animation.time_ms)
139
        goal.scale = animation.scale
140

    
141
        #send the goal to the server
142
        self.animation_client.send_goal(goal)
143

    
144
        #wait for the server to finish
145
        if (blocking):
146
            timed_out = self.animation_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
147
            if (timed_out):
148
                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
149

    
150
        self.logger.debug("animation rpc done")
151

    
152
    def publish_gaze_target(self, gaze, blocking):
153
        """publish a gaze target via mw
154
        :param gaze: gaze to set
155
        :param blocking: True if this call should block until execution finished on robot
156
        """
157
        self.logger.debug("calling the gaze rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
158

    
159
        #create a goal to send to the action server.
160
        goal = gazetargetGoal()
161
        goal.pan  = gaze.pan
162
        goal.tilt = gaze.tilt
163
        goal.roll = gaze.roll
164
        goal.vergence = gaze.vergence
165
        goal.pan_offset  = gaze.pan_offset
166
        goal.tilt_offset = gaze.tilt_offset
167

    
168
        #type
169
        if (gaze.gaze_type == RobotGaze.GAZETARGET_ABSOLUTE):
170
            goal.gaze_type = gazetargetGoal.GAZETARGET_ABSOLUTE
171
        else:
172
            goal.gaze_type = gazetargetGoal.GAZETARGET_RELATIVE
173

    
174
        goal.timestamp = rospy.Time.from_sec(gaze.timestamp)
175

    
176
        #send the goal to the server
177
        self.gazetarget_client.send_goal(goal)
178

    
179
        #wait for the server to finish
180
        if (blocking):
181
            timed_out = self.gazetarget_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
182
            if (timed_out):
183
                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
184

    
185

    
186
        self.logger.debug("gaze rpc done")
187

    
188
    def publish_mouth_target(self, mouth, blocking):
189
        """publish a mouth target via mw
190
        :param mouth: mouth value to set
191
        :param blocking: True if this call should block until execution finished on robot
192
        """
193
        self.logger.debug("calling the mouth rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
194

    
195
        #create a goal to send to the action server.
196
        goal = mouthtargetGoal()
197
        goal.opening_left  = mouth.opening_left
198
        goal.opening_center = mouth.opening_center
199
        goal.opening_right = mouth.opening_right
200
        goal.position_left = mouth.position_left
201
        goal.position_center  = mouth.position_center
202
        goal.position_right = mouth.position_right
203

    
204
        #send the goal to the server
205
        self.mouthtarget_client.send_goal(goal)
206

    
207
        #wait for the server to finish
208
        if (blocking):
209
            timed_out = self.mouthtarget_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
210
            if (timed_out):
211
                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
212

    
213
        self.logger.debug("mouth rpc done")
214

    
215
    def publish_speech(self, text_, blocking):
216
        """publish a tts request via mw
217
        :param text_: text to synthesize and speak
218
        :param blocking: True if this call should block until execution finished on robot
219
        """
220
        self.logger.debug("calling the speech rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
221

    
222
        #create a goal to send to the action server.
223
        goal = speechGoal(text=text_)
224

    
225
        #send the goal to the server
226
        self.speech_client.send_goal(goal)
227

    
228
        #wait for the server to finish
229
        if (blocking):
230
            timed_out = self.speech_client.wait_for_result(rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
231
            if (timed_out):
232
                self.logger.error("%s timed out waiting for result" % (sys._getframe().f_code.co_name))
233

    
234
        self.logger.debug("speech rpc done")
235

    
236
    #######################################################################
237
    # some helpers
238
    def convert_animationtype_to_rosval(self, value):
239
        """convert RobotAnimation.value to ROS animation value
240
        :param value: RobotAnimation.* id to convert to rsb id
241
        """
242
        #NOTE: this convertion is important as the actual integer values of
243
        #      thy python api and the protobuf might be different
244
        if (value == RobotAnimation.IDLE):
245
            return animationGoal.IDLE
246
        elif (value == RobotAnimation.HEAD_NOD):
247
            return animationGoal.HEAD_NOD
248
        elif (value == RobotAnimation.HEAD_SHAKE):
249
            return animationGoal.HEAD_SHAKE
250
        elif (value == RobotAnimation.EYEBLINK_L):
251
            return animationGoal.EYEBLINK_L
252
        elif (value == RobotAnimation.EYEBLINK_R):
253
            return  animationGoal.EYEBLINK_R
254
        elif (value == RobotAnimation.EYEBLINK_BOTH):
255
            return  animationGoal.EYEBLINK_BOTH
256
        elif (value == RobotAnimation.EYEBROWS_RAISE):
257
            return  animationGoal.EYEBROWS_RAISE
258
        elif (value == RobotAnimation.EYEBROWS_LOWER):
259
            return  animationGoal.EYEBROWS_LOWER
260
        else:
261
            self.logger.error("invalid animation type %d\n" % (value))
262
            return  animationGoal.NEUTRAL
263

    
264
    def convert_emotiontype_to_rosval(self, value):
265
        """convert RobotEmotion.value to ROS animation value
266
        :param value: RobotEmotion.* id to convert to ros id
267
        """
268
        #NOTE: this convertion is important as the actual integer values of
269
        #      thy python api and the protobuf might be different
270

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