Statistics
| Branch: | Tag: | Revision:

hlrc / client / cpp / src / MiddlewareROS.cpp @ 482adb6d

History | View | Annotate | Download (8.588 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
#ifdef ROS_SUPPORT
29

    
30
#include "MiddlewareROS.h"
31
#include <stdio.h>
32
#include <boost/algorithm/string.hpp>
33
#include <boost/range/algorithm_ext/erase.hpp>
34
#include <boost/range/algorithm/remove_if.hpp>
35

    
36
using namespace std;
37

    
38
MiddlewareROS::MiddlewareROS(string scope) : Middleware(scope) {
39
        printf("> new MiddlewareROS() on base scope '%s'\n", base_scope.c_str());
40
        init();
41
}
42

    
43
template <typename actionspec>
44
actionlib::SimpleActionClient<actionspec>* create_action_client(string scope) {
45
        printf("> starting SimpleActionClient on %s\n", scope.c_str());
46

    
47
        actionlib::SimpleActionClient<actionspec>* ac = new actionlib::SimpleActionClient<actionspec>(scope, true);
48

    
49
        if (!ac->waitForServer(ros::Duration(1))) {
50
                char buf[256];
51
                snprintf(buf, 256, "ERROR: action service %s not ready", scope.c_str());
52
                throw runtime_error(buf);
53
        }
54
        return ac;
55
}
56

    
57
void MiddlewareROS::init(void) {
58
        printf("> MiddlewareROS::init()\n");
59

    
60
        string scope = base_scope + "/set";
61

    
62
        string node_name = "hlrc_client__" + base_scope;
63
        node_name.erase(boost::remove_if(node_name, boost::is_any_of("/")), node_name.end());
64

    
65
        printf("> registering on ROS as node %s, scope = %s\n", node_name.c_str(), scope.c_str());
66
        if (!ros::isInitialized()) {
67
                ros::M_string no_remapping;
68
                ros::init(no_remapping, node_name);
69
        }
70

    
71
        // create node handle
72
        // ros_node_handle = new ros::NodeHandle();
73
        // node_handle = std::shared_ptr<ros::NodeHandle>(new ros::NodeHandle());
74

    
75
        printf("> setting up ROS action clients...\n");
76
        animation_ac = create_action_client<hlrc_server::animationAction>(scope + "/animation");
77
        utterance_ac = create_action_client<hlrc_server::utteranceAction>(scope + "/utterance");
78
        current_emotionstate_ac = create_action_client<hlrc_server::emotionstateAction>(scope + "/currentEmotion");
79
        default_emotionstate_ac = create_action_client<hlrc_server::emotionstateAction>(scope + "/defaultEmotion");
80
        gazetarget_ac = create_action_client<hlrc_server::gazetargetAction>(scope + "/gaze");
81
        lookattarget_ac = create_action_client<hlrc_server::lookattargetAction>(scope + "/lookat");
82
        mouthtarget_ac = create_action_client<hlrc_server::mouthtargetAction>(scope + "/mouth");
83
        speech_ac = create_action_client<hlrc_server::speechAction>(scope + "/speech");
84

    
85
        printf("> init done.\n");
86
}
87

    
88
void MiddlewareROS::publish_emotion(string scope_target, RobotEmotion e, bool blocking) {
89
        hlrc_server::emotionstateGoal goal;
90

    
91
        switch (e.value) {
92
                default:
93
                        printf("> WANRING: invalid emotion id %d. defaulting to NEUTRAL\n", e.value);
94
                        // fall through:
95
                case (RobotEmotion::NEUTRAL):
96
                        goal.value = hlrc_server::emotionstateGoal::NEUTRAL;
97
                        break;
98
                case (RobotEmotion::HAPPY):
99
                        goal.value = hlrc_server::emotionstateGoal::HAPPY;
100
                        break;
101
                case (RobotEmotion::SAD):
102
                        goal.value = hlrc_server::emotionstateGoal::SAD;
103
                        break;
104
                case (RobotEmotion::ANGRY):
105
                        goal.value = hlrc_server::emotionstateGoal::ANGRY;
106
                        break;
107
                case (RobotEmotion::SURPRISED):
108
                        goal.value = hlrc_server::emotionstateGoal::SURPRISED;
109
                        break;
110
                case (RobotEmotion::FEAR):
111
                        goal.value = hlrc_server::emotionstateGoal::FEAR;
112
                        break;
113
        }
114

    
115
        goal.duration = e.time_ms;
116

    
117
        actionlib::SimpleActionClient<hlrc_server::emotionstateAction>* ac;
118
        if (scope_target == "defaultEmotion") {
119
                ac = default_emotionstate_ac;
120
        }
121
        else {
122
                ac = current_emotionstate_ac;
123
        }
124

    
125
        // send
126
        ac->sendGoal(goal);
127

    
128
        if (blocking) {
129
                bool finished_before_timeout = ac->waitForResult(ros::Duration(ROS_ACTION_CALL_TIMEOUT));
130
                if (!finished_before_timeout) {
131
                        printf("> ERROR: blocking call timed out!\n");
132
                }
133
        }
134
}
135

    
136
void MiddlewareROS::publish_current_emotion(RobotEmotion e, bool blocking) {
137
        publish_emotion("currentEmotion", e, blocking);
138
}
139

    
140
void MiddlewareROS::publish_default_emotion(RobotEmotion e, bool blocking) {
141
        publish_emotion("defaultEmotion", e, blocking);
142
}
143

    
144
void MiddlewareROS::publish_gaze_target(RobotGaze target, bool blocking) {
145
        hlrc_server::gazetargetGoal goal;
146

    
147
        goal.pan = target.pan;
148
        goal.tilt = target.tilt;
149
        goal.roll = target.roll;
150
        goal.vergence = target.vergence;
151

    
152
        goal.tilt_offset = target.tilt_offset;
153
        goal.pan_offset = target.pan_offset;
154

    
155
        // timestamp:
156
        goal.gaze_timestamp.sec = target.gaze_timestamp.sec;
157
        goal.gaze_timestamp.nsec = target.gaze_timestamp.nsec;
158

    
159
        if (target.gaze_type == RobotGaze::ABSOLUTE) {
160
                goal.gaze_type = hlrc_server::gazetargetGoal::GAZETARGET_ABSOLUTE;
161
        }
162
        else {
163
                goal.gaze_type = hlrc_server::gazetargetGoal::GAZETARGET_RELATIVE;
164
        }
165

    
166
        // send
167
        gazetarget_ac->sendGoal(goal);
168

    
169
        if (blocking) {
170
                bool finished_before_timeout = gazetarget_ac->waitForResult(ros::Duration(ROS_ACTION_CALL_TIMEOUT));
171
                if (!finished_before_timeout) {
172
                        printf("> ERROR: blocking call timed out!\n");
173
                }
174
        }
175
}
176

    
177
void MiddlewareROS::publish_lookat_target(float x, float y, float z, const string frame_id, bool blocking, float roll) {
178
        hlrc_server::lookattargetGoal goal;
179
        goal.point.header.frame_id = frame_id;
180
        goal.point.header.stamp = ros::Time::now();
181

    
182
        geometry_msgs::Point& p = goal.point.point;
183
        p.x = x;
184
        p.y = y;
185
        p.z = z;
186
        goal.roll = roll;
187

    
188
        // send
189
        lookattarget_ac->sendGoal(goal);
190

    
191
        if (blocking) {
192
                bool finished_before_timeout = gazetarget_ac->waitForResult(ros::Duration(ROS_ACTION_CALL_TIMEOUT));
193
                if (!finished_before_timeout) {
194
                        printf("> ERROR: blocking call timed out!\n");
195
                }
196
        }
197
}
198

    
199
void MiddlewareROS::publish_mouth_target(RobotMouth target, bool blocking) {
200
        hlrc_server::mouthtargetGoal goal;
201

    
202
        goal.position_left = target.position_left;
203
        goal.position_center = target.position_center;
204
        goal.position_right = target.position_right;
205

    
206
        goal.opening_left = target.opening_left;
207
        goal.opening_center = target.opening_center;
208
        goal.opening_right = target.opening_right;
209

    
210
        // send
211
        mouthtarget_ac->sendGoal(goal);
212

    
213
        if (blocking) {
214
                bool finished_before_timeout = mouthtarget_ac->waitForResult(ros::Duration(ROS_ACTION_CALL_TIMEOUT));
215
                if (!finished_before_timeout) {
216
                        printf("> ERROR: blocking call timed out!\n");
217
                }
218
        }
219
}
220

    
221
void MiddlewareROS::publish_head_animation(RobotHeadAnimation a, bool blocking) {
222
        hlrc_server::animationGoal goal;
223

    
224
        switch (a.value) {
225
                default:
226
                        printf("> WANRING: invalid animation id %d. defaulting to IDLE", a.value);
227
                        // fall through:
228
                case (RobotHeadAnimation::IDLE):
229
                        goal.target = hlrc_server::animationGoal::IDLE;
230
                        break;
231
                case (RobotHeadAnimation::HEAD_NOD):
232
                        goal.target = hlrc_server::animationGoal::HEAD_NOD;
233
                        break;
234
                case (RobotHeadAnimation::HEAD_SHAKE):
235
                        goal.target = hlrc_server::animationGoal::HEAD_SHAKE;
236
                        break;
237
                case (RobotHeadAnimation::EYEBLINK_L):
238
                        goal.target = hlrc_server::animationGoal::EYEBLINK_L;
239
                        break;
240
                case (RobotHeadAnimation::EYEBLINK_R):
241
                        goal.target = hlrc_server::animationGoal::EYEBLINK_R;
242
                        break;
243
                case (RobotHeadAnimation::EYEBLINK_BOTH):
244
                        goal.target = hlrc_server::animationGoal::EYEBLINK_BOTH;
245
                        break;
246
                case (RobotHeadAnimation::EYEBROWS_RAISE):
247
                        goal.target = hlrc_server::animationGoal::EYEBROWS_RAISE;
248
                        break;
249
                case (RobotHeadAnimation::EYEBROWS_LOWER):
250
                        goal.target = hlrc_server::animationGoal::EYEBROWS_LOWER;
251
                        break;
252
        }
253

    
254
        goal.repetitions = a.repetitions;
255
        goal.scale = a.scale;
256
        goal.duration_each = a.time_ms;
257

    
258
        // send
259
        animation_ac->sendGoal(goal);
260

    
261
        if (blocking) {
262
                bool finished_before_timeout = animation_ac->waitForResult(ros::Duration(ROS_ACTION_CALL_TIMEOUT));
263
                if (!finished_before_timeout) {
264
                        printf("> ERROR: blocking call timed out!\n");
265
                }
266
        }
267
}
268

    
269
void MiddlewareROS::publish_speech(string text, bool blocking) {
270
        hlrc_server::speechGoal goal;
271

    
272
        goal.text = text;
273

    
274
        // send
275
        speech_ac->sendGoal(goal);
276

    
277
        if (blocking) {
278
                bool finished_before_timeout = speech_ac->waitForResult(ros::Duration(ROS_ACTION_CALL_TIMEOUT));
279
                if (!finished_before_timeout) {
280
                        printf("> ERROR: blocking call timed out!\n");
281
                }
282
        }
283
}
284

    
285
#endif