hlrc / client / cpp / src / MiddlewareRSB.cpp @ f150aab5
History | View | Annotate | Download (8.79 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 |
|
29 |
#ifdef RSB_SUPPORT
|
30 |
|
31 |
#include "MiddlewareRSB.h" |
32 |
#include <rsb/converter/Repository.h> |
33 |
#include <rsb/converter/ProtocolBufferConverter.h> |
34 |
|
35 |
#include <rst/animation/EmotionExpression.pb.h> |
36 |
#include <rst/animation/BinocularHeadGaze.pb.h> |
37 |
#include <rst/animation/HeadAnimation.pb.h> |
38 |
#include <rst/audition/Utterance.pb.h> |
39 |
#include <rst/audition/SoundChunk.pb.h> |
40 |
#include <boost/algorithm/string.hpp> |
41 |
#include <boost/range/algorithm_ext/erase.hpp> |
42 |
|
43 |
using namespace std; |
44 |
using namespace rsb; |
45 |
using namespace rsb::patterns; |
46 |
|
47 |
MiddlewareRSB::MiddlewareRSB(string scope) : Middleware(scope) {
|
48 |
printf("> new MiddlewareRSB() on base scope '%s'\n", base_scope.c_str());
|
49 |
init(); |
50 |
} |
51 |
|
52 |
void MiddlewareRSB::init(void) { |
53 |
printf("> MiddlewareRSB::init() registering converters\n");
|
54 |
|
55 |
try {
|
56 |
// converter for EmotionState
|
57 |
rsb::converter::Converter<string>::Ptr emotionStateConverter(
|
58 |
new rsb::converter::ProtocolBufferConverter<rst::animation::EmotionExpression>());
|
59 |
rsb::converter::converterRepository<string>()->registerConverter(emotionStateConverter);
|
60 |
|
61 |
// converter for Utterance
|
62 |
// rsb::converter::Converter<string>::Ptr UtteranceConverter(new
|
63 |
// rsb::converter::ProtocolBufferConverter<rst::audition::Utterance>());
|
64 |
// rsb::converter::converterRepository<string>()->registerConverter(UtteranceConverter);
|
65 |
|
66 |
// converter for GazeTarget
|
67 |
rsb::converter::Converter<string>::Ptr gazeTargetConverter(
|
68 |
new rsb::converter::ProtocolBufferConverter<rst::animation::BinocularHeadGaze>());
|
69 |
rsb::converter::converterRepository<string>()->registerConverter(gazeTargetConverter);
|
70 |
|
71 |
// converter for MouthTarget
|
72 |
/// rsb::converter::Converter<string>::Ptr mouthTargetConverter(new
|
73 |
/// rsb::converter::ProtocolBufferConverter<rst::robot::MouthTarget>());
|
74 |
/// rsb::converter::converterRepository<string>()->registerConverter(mouthTargetConverter);
|
75 |
|
76 |
// converter for Animation
|
77 |
rsb::converter::Converter<string>::Ptr animationConverter(
|
78 |
new rsb::converter::ProtocolBufferConverter<rst::animation::HeadAnimation>());
|
79 |
rsb::converter::converterRepository<string>()->registerConverter(animationConverter);
|
80 |
} |
81 |
catch (std::invalid_argument e) {
|
82 |
printf("> converters already registered\n");
|
83 |
} |
84 |
|
85 |
// first get a factory instance that is used to create RSB domain objects
|
86 |
Factory& factory = getFactory(); |
87 |
|
88 |
// get server
|
89 |
string scope = base_scope + "/set/"; |
90 |
hlrc_server = factory.createRemoteServer(scope); |
91 |
|
92 |
printf("> init done\n");
|
93 |
} |
94 |
|
95 |
void MiddlewareRSB::publish_emotion(string scope_target, RobotEmotion e, bool blocking) { |
96 |
boost::shared_ptr<rst::animation::EmotionExpression> request(new rst::animation::EmotionExpression());
|
97 |
|
98 |
switch (e.value) {
|
99 |
default:
|
100 |
printf("> WANRING: invalid emotion id %d. defaulting to NEUTRAL\n", e.value);
|
101 |
// fall through:
|
102 |
case (RobotEmotion::NEUTRAL):
|
103 |
request->set_emotion(rst::animation::EmotionExpression::NEUTRAL); |
104 |
break;
|
105 |
case (RobotEmotion::HAPPY):
|
106 |
request->set_emotion(rst::animation::EmotionExpression::HAPPY); |
107 |
break;
|
108 |
case (RobotEmotion::SAD):
|
109 |
request->set_emotion(rst::animation::EmotionExpression::SAD); |
110 |
break;
|
111 |
case (RobotEmotion::ANGRY):
|
112 |
request->set_emotion(rst::animation::EmotionExpression::ANGRY); |
113 |
break;
|
114 |
case (RobotEmotion::SURPRISED):
|
115 |
request->set_emotion(rst::animation::EmotionExpression::SURPRISED); |
116 |
break;
|
117 |
case (RobotEmotion::FEAR):
|
118 |
request->set_emotion(rst::animation::EmotionExpression::FEAR); |
119 |
break;
|
120 |
} |
121 |
|
122 |
request->set_duration(e.time_ms); |
123 |
|
124 |
if (blocking) {
|
125 |
hlrc_server->call<rst::animation::EmotionExpression>(scope_target, request); |
126 |
} |
127 |
else {
|
128 |
hlrc_server->callAsync<rst::animation::EmotionExpression>(scope_target, request); |
129 |
} |
130 |
} |
131 |
|
132 |
void MiddlewareRSB::publish_current_emotion(RobotEmotion e, bool blocking) { |
133 |
publish_emotion("currentEmotion", e, blocking);
|
134 |
} |
135 |
|
136 |
void MiddlewareRSB::publish_default_emotion(RobotEmotion e, bool blocking) { |
137 |
publish_emotion("defaultEmotion", e, blocking);
|
138 |
} |
139 |
|
140 |
void MiddlewareRSB::publish_gaze_target(RobotGaze incoming_target, bool blocking) { |
141 |
boost::shared_ptr<rst::animation::BinocularHeadGaze> request(new rst::animation::BinocularHeadGaze());
|
142 |
|
143 |
boost::shared_ptr<rst::geometry::SphericalDirectionFloat> target(new rst::geometry::SphericalDirectionFloat());
|
144 |
target->set_azimuth(incoming_target.pan); |
145 |
target->set_elevation(incoming_target.tilt); |
146 |
request->set_allocated_target(target.get()); |
147 |
|
148 |
request->set_eye_vergence(incoming_target.vergence); |
149 |
|
150 |
boost::shared_ptr<rst::geometry::SphericalDirectionFloat> offset(new rst::geometry::SphericalDirectionFloat());
|
151 |
offset->set_azimuth(incoming_target.pan_offset); |
152 |
offset->set_elevation(incoming_target.tilt_offset); |
153 |
request->set_allocated_offset(offset.get()); |
154 |
|
155 |
if (blocking) {
|
156 |
hlrc_server->call<rst::animation::BinocularHeadGaze>("gaze", request);
|
157 |
} |
158 |
else {
|
159 |
hlrc_server->callAsync<rst::animation::BinocularHeadGaze>("gaze", request);
|
160 |
} |
161 |
} |
162 |
|
163 |
void MiddlewareRSB::publish_lookat_target(float x, float y, float z, const std::string frame_id, bool blocking, float roll) { |
164 |
std::cerr << "not yet implemented" << std::endl;
|
165 |
} |
166 |
|
167 |
void MiddlewareRSB::publish_mouth_target(RobotMouth target, bool blocking) { |
168 |
/*
|
169 |
boost::shared_ptr<rst::robot::MouthTarget> request(new rst::robot::MouthTarget());
|
170 |
|
171 |
request->set_position_left( target.position_left);
|
172 |
request->set_position_center(target.position_center);
|
173 |
request->set_position_right( target.position_right);
|
174 |
|
175 |
request->set_opening_left( target.opening_left);
|
176 |
request->set_opening_center(target.opening_center);
|
177 |
request->set_opening_right( target.opening_right);
|
178 |
|
179 |
if (blocking){
|
180 |
hlrc_server->call<rst::robot::MouthTarget>("mouth", request);
|
181 |
}else{
|
182 |
hlrc_server->callAsync<rst::robot::MouthTarget>("mouth", request);
|
183 |
}
|
184 |
*/
|
185 |
printf("> ERROR: mouth targets not yet implemented in RSB middleware!\n");
|
186 |
} |
187 |
|
188 |
void MiddlewareRSB::publish_head_animation(RobotHeadAnimation a, bool blocking) { |
189 |
boost::shared_ptr<rst::animation::HeadAnimation> request(new rst::animation::HeadAnimation());
|
190 |
|
191 |
switch (a.value) {
|
192 |
default:
|
193 |
printf("> WANRING: invalid animation id %d. defaulting to IDLE", a.value);
|
194 |
// fall through:
|
195 |
case (RobotHeadAnimation::IDLE):
|
196 |
request->set_animation(rst::animation::HeadAnimation::IDLE); |
197 |
break;
|
198 |
case (RobotHeadAnimation::HEAD_NOD):
|
199 |
request->set_animation(rst::animation::HeadAnimation::HEAD_NOD); |
200 |
break;
|
201 |
case (RobotHeadAnimation::HEAD_SHAKE):
|
202 |
request->set_animation(rst::animation::HeadAnimation::HEAD_SHAKE); |
203 |
break;
|
204 |
case (RobotHeadAnimation::EYEBLINK_L):
|
205 |
request->set_animation(rst::animation::HeadAnimation::EYEBLINK_LEFT); |
206 |
break;
|
207 |
case (RobotHeadAnimation::EYEBLINK_R):
|
208 |
request->set_animation(rst::animation::HeadAnimation::EYEBLINK_RIGHT); |
209 |
break;
|
210 |
case (RobotHeadAnimation::EYEBLINK_BOTH):
|
211 |
request->set_animation(rst::animation::HeadAnimation::EYEBLINK_BOTH); |
212 |
break;
|
213 |
case (RobotHeadAnimation::EYEBROWS_RAISE):
|
214 |
request->set_animation(rst::animation::HeadAnimation::EYEBROWS_RAISE); |
215 |
break;
|
216 |
case (RobotHeadAnimation::EYEBROWS_LOWER):
|
217 |
request->set_animation(rst::animation::HeadAnimation::EYEBROWS_LOWER); |
218 |
break;
|
219 |
case (RobotHeadAnimation::ENGAGEMENT_LEFT):
|
220 |
request->set_animation(rst::animation::HeadAnimation::ENGAGEMENT_LEFT); |
221 |
break;
|
222 |
case (RobotHeadAnimation::ENGAGEMENT_RIGHT):
|
223 |
request->set_animation(rst::animation::HeadAnimation::ENGAGEMENT_RIGHT); |
224 |
break;
|
225 |
} |
226 |
|
227 |
request->set_repetitions(a.repetitions); |
228 |
request->set_emphasis_scale(a.scale); |
229 |
request->set_duration_each(a.time_ms); |
230 |
|
231 |
if (blocking) {
|
232 |
hlrc_server->call<rst::animation::HeadAnimation>("animation", request);
|
233 |
} |
234 |
else {
|
235 |
hlrc_server->callAsync<rst::animation::HeadAnimation>("animation", request);
|
236 |
} |
237 |
} |
238 |
|
239 |
void MiddlewareRSB::publish_speech(string text, bool blocking) { |
240 |
// say it
|
241 |
boost::shared_ptr<std::string> request(new string(text)); |
242 |
|
243 |
if (blocking) {
|
244 |
hlrc_server->call<std::string>("speech", request); |
245 |
} |
246 |
else {
|
247 |
hlrc_server->callAsync<std::string>("speech", request); |
248 |
} |
249 |
} |
250 |
|
251 |
#endif
|