Statistics
| Branch: | Tag: | Revision:

hlrc / client / python / hlrc_client / MiddlewareROS.py @ 67f533d7

History | View | Annotate | Download (12.537 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
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 mouthtarget action client")
90
        self.mouthtarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/mouth", mouthtargetAction)
91
        self.mouthtarget_client.wait_for_server()
92

    
93
        self.logger.info("MiddlewareROS initialised")
94

    
95
    #######################################################################
96
    def is_running(self):
97
        return not rospy.is_shutdown()
98

    
99
    #######################################################################
100
    def publish_emotion(self, em_type, emotion, blocking):
101
        """publish an emotion via mw
102
        :param em_type: type of emotion (RobotEmotion::TYPE_DEFAULT or RobotEmotion::TYPE_CURRENT)
103
        :param emotion: emotion to set
104
        :param blocking: True if this call should block until execution finished on robot
105
        """
106
        self.logger.debug("calling the emotion rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
107

    
108
        #create a goal to send to the action server.
109
        goal = emotionstateGoal()
110
        goal.value    = self.convert_emotiontype_to_rosval(emotion.value)
111
        goal.duration =  int(emotion.time_ms)
112

    
113
        #which client do we use?
114
        if (em_type == RobotEmotion.TYPE_DEFAULT):
115
            client = self.default_emotion_client
116
        else:
117
            client = self.current_emotion_client
118

    
119
        #send the goal to the server
120
        if (blocking):
121
            #send and wait:
122
            state = client.send_goal_and_wait(goal, execute_timeout = rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
123
            if (state != GoalStatus.SUCCEEDED):
124
                self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name))
125
        else:
126
            #non blocking, fire & forget
127
            client.send_goal(goal)
128

    
129
        self.logger.debug("emotion rpc done")
130

    
131
    def publish_default_emotion(self, emotion, blocking):
132
        self.publish_emotion(RobotEmotion.TYPE_DEFAULT, emotion, blocking)
133

    
134
    def publish_current_emotion(self, emotion, blocking):
135
        self.publish_emotion(RobotEmotion.TYPE_CURRENT, emotion, blocking)
136

    
137
    def publish_head_animation(self, animation, blocking):
138
        """publish an head animation via mw
139
        :param animation: animation to set
140
        :param blocking: True if this call should block until execution finished on robot
141
        """
142
        self.logger.debug("calling the animation rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
143

    
144
        #create a goal to send to the action server.
145
        goal = animationGoal()
146
        goal.target = self.convert_animationtype_to_rosval(animation.value)
147
        goal.repetitions = animation.repetitions
148
        goal.duration_each =  int(animation.time_ms)
149
        goal.scale = animation.scale
150

    
151
        #send the goal to the server
152
        if (blocking):
153
            #send and wait:
154
            state = self.animation_client.send_goal_and_wait(goal, execute_timeout = rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
155
            if (state != GoalStatus.SUCCEEDED):
156
                self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name))
157
        else:
158
            #non blocking, fire & forget
159
            self.animation_client.send_goal(goal)
160

    
161
        self.logger.debug("animation rpc done")
162

    
163
    def publish_gaze_target(self, gaze, blocking):
164
        """publish a gaze target via mw
165
        :param gaze: gaze to set
166
        :param blocking: True if this call should block until execution finished on robot
167
        """
168
        self.logger.debug("calling the gaze rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
169

    
170
        #create a goal to send to the action server.
171
        goal = gazetargetGoal()
172
        goal.pan  = gaze.pan
173
        goal.tilt = gaze.tilt
174
        goal.roll = gaze.roll
175
        goal.vergence = gaze.vergence
176
        goal.pan_offset  = gaze.pan_offset
177
        goal.tilt_offset = gaze.tilt_offset
178

    
179
        #type
180
        if (gaze.gaze_type == RobotGaze.GAZETARGET_ABSOLUTE):
181
            goal.gaze_type = gazetargetGoal.GAZETARGET_ABSOLUTE
182
        else:
183
            goal.gaze_type = gazetargetGoal.GAZETARGET_RELATIVE
184

    
185
        goal.gaze_timestamp = rospy.Time.from_sec(gaze.gaze_timestamp.to_seconds())
186

    
187
        #send the goal to the server
188
        if (blocking):
189
            #send and wait:
190
            state = self.gazetarget_client.send_goal_and_wait(goal, execute_timeout = rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
191
            if (state != GoalStatus.SUCCEEDED):
192
                self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name))
193
        else:
194
            #non blocking, fire & forget
195
            self.gazetarget_client.send_goal(goal)
196

    
197
        self.logger.debug("gaze rpc done")
198

    
199
    def publish_mouth_target(self, mouth, blocking):
200
        """publish a mouth target via mw
201
        :param mouth: mouth value to set
202
        :param blocking: True if this call should block until execution finished on robot
203
        """
204
        self.logger.debug("calling the mouth rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
205

    
206
        #create a goal to send to the action server.
207
        goal = mouthtargetGoal()
208
        goal.opening_left  = mouth.opening_left
209
        goal.opening_center = mouth.opening_center
210
        goal.opening_right = mouth.opening_right
211
        goal.position_left = mouth.position_left
212
        goal.position_center  = mouth.position_center
213
        goal.position_right = mouth.position_right
214

    
215
        #send the goal to the server
216
        if (blocking):
217
            #send and wait:
218
            state = self.mouthtarget_client.send_goal_and_wait(goal, execute_timeout = rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
219
            if (state != GoalStatus.SUCCEEDED):
220
                self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name))
221
        else:
222
            #non blocking, fire & forget
223
            self.mouthtarget_client.send_goal(goal)
224

    
225
        self.logger.debug("mouth rpc done")
226

    
227
    def publish_speech(self, text_, blocking):
228
        """publish a tts request via mw
229
        :param text_: text to synthesize and speak
230
        :param blocking: True if this call should block until execution finished on robot
231
        """
232
        self.logger.debug("calling the speech rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING"))
233

    
234
        #create a goal to send to the action server.
235
        goal = speechGoal(text=text_)
236

    
237
        #send the goal to the server
238
        if (blocking):
239
            #send and wait:
240
            state = self.speech_client.send_goal_and_wait(goal, execute_timeout = rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT))
241
            if (state != GoalStatus.SUCCEEDED):
242
                self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name))
243
        else:
244
            #non blocking, fire & forget
245
            self.speech_client.send_goal(goal)
246

    
247
        self.logger.debug("speech rpc done")
248

    
249
    #######################################################################
250
    # some helpers
251
    def convert_animationtype_to_rosval(self, value):
252
        """convert RobotAnimation.value to ROS animation value
253
        :param value: RobotAnimation.* id to convert to rsb id
254
        """
255
        #NOTE: this convertion is important as the actual integer values of
256
        #      thy python api and the protobuf might be different
257
        if (value == RobotAnimation.IDLE):
258
            return animationGoal.IDLE
259
        elif (value == RobotAnimation.HEAD_NOD):
260
            return animationGoal.HEAD_NOD
261
        elif (value == RobotAnimation.HEAD_SHAKE):
262
            return animationGoal.HEAD_SHAKE
263
        elif (value == RobotAnimation.EYEBLINK_L):
264
            return animationGoal.EYEBLINK_L
265
        elif (value == RobotAnimation.EYEBLINK_R):
266
            return  animationGoal.EYEBLINK_R
267
        elif (value == RobotAnimation.EYEBLINK_BOTH):
268
            return  animationGoal.EYEBLINK_BOTH
269
        elif (value == RobotAnimation.EYEBROWS_RAISE):
270
            return  animationGoal.EYEBROWS_RAISE
271
        elif (value == RobotAnimation.EYEBROWS_LOWER):
272
            return  animationGoal.EYEBROWS_LOWER
273
        else:
274
            self.logger.error("invalid animation type %d\n" % (value))
275
            return  animationGoal.NEUTRAL
276

    
277
    def convert_emotiontype_to_rosval(self, value):
278
        """convert RobotEmotion.value to ROS animation value
279
        :param value: RobotEmotion.* id to convert to ros id
280
        """
281
        #NOTE: this convertion is important as the actual integer values of
282
        #      thy python api and the protobuf might be different
283

    
284
        if (value == RobotEmotion.NEUTRAL):
285
            return emotionstateGoal.NEUTRAL
286
        elif (value == RobotEmotion.HAPPY):
287
            return emotionstateGoal.HAPPY
288
        elif (value == RobotEmotion.SAD):
289
            return emotionstateGoal.SAD
290
        elif (value == RobotEmotion.ANGRY):
291
            return emotionstateGoal.ANGRY
292
        elif (value == RobotEmotion.SURPRISED):
293
            return  emotionstateGoal.SURPRISED
294
        elif (value == RobotEmotion.FEAR):
295
            return emotionstateGoal.FEAR
296
        else:
297
            self.logger.error("invalid emotion type %d\n" % (value))
298
            return  emotionstateGoal.NEUTRAL