Project: engagement_recognition License: BSD Dependencies:
Used by:
None |
engagement_recognition/src/recognition/recognizers/adjacency_pair/ap_robot_waiting_state.cppGo to the documentation of this file.00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Worcester Polytechnic Institute 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Worcester Polytechnic Institute. nor the names 00018 * of its contributors may be used to endorse or promote products 00019 * derived from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 // @author Brett Ponsler (bponsler (at) wpi (dot) edu) 00035 #include "ap_robot_waiting_state.h" 00036 00037 #include "../../events/event_factory.h" 00038 #include "../../lib/engagement_params.h" 00039 #include "../../objects/engagement_objects.h" 00040 00041 APRobotWaitingState::APRobotWaitingState() : 00042 State(APRobotWaitingState::type(), "", NULL) 00043 { 00044 // Set the logger based on this type of recognizer 00045 this->setLogger(EngagementParams::getStateTag(APRobotWaitingState::type())); 00046 00047 this->warn("Initialized with an invalid actor, " 00048 "robot and EventSink."); 00049 } 00050 00051 APRobotWaitingState::APRobotWaitingState(std::string actor, EventSink *sink) : 00052 State(APRobotWaitingState::type(), actor, sink) 00053 { 00054 // Set the logger based on this type of recognizer 00055 this->setLogger(sink->getLogger(), 00056 EngagementParams::getStateTag(APRobotWaitingState::type())); 00057 } 00058 00059 APRobotWaitingState::~APRobotWaitingState() 00060 { 00061 } 00062 00063 Event APRobotWaitingState::received(std::string topic, engagement_msgs::ActorIDStatus *message) 00064 { 00065 if (topic == engagement::RECOGNITION_NAMESPACE + "/" + 00066 engagement::HUMAN_NAMESPACE + "/" + 00067 engagement::RECOG_STATUS_TOPIC.c_str()) 00068 return this->engageStatusCallback(message); 00069 00070 return Event(); 00071 } 00072 00073 Event APRobotWaitingState::received(std::string topic, engagement_msgs::Performance *message) 00074 { 00075 if (topic == engagement::VISION_NAMESPACE + "/" + engagement::PERFORMING_NOD_TOPIC) 00076 return this->visionNodCallback(message); 00077 else if (topic == engagement::VISION_NAMESPACE + "/" + engagement::PERFORMING_SHAKE_TOPIC) 00078 return this->visionShakeCallback(message); 00079 else if (topic == engagement::VISION_NAMESPACE + "/" + engagement::PERFORMING_EXTENDED_ACTION_TOPIC) 00080 return this->visionExtendedActionCallback(message); 00081 else if (topic == engagement::VISION_NAMESPACE + "/" + engagement::PERFORMING_POINT_TOPIC) 00082 return this->visionPointCallback(message); 00083 else if (topic == engagement::VISION_NAMESPACE + "/" + engagement::PERFORMING_LOOK_TOPIC) 00084 return this->visionLookCallback(message); 00085 00086 return Event(); 00087 } 00088 00089 Event APRobotWaitingState::received(std::string topic, engagement_msgs::Speech *message) 00090 { 00091 if (topic == engagement::PERFORMING_NAMESPACE + "/" + engagement::PERFORMING_UTTERANCE_TOPIC) 00092 return this->performingUtteranceCallback(message); 00093 00094 return Event(); 00095 } 00096 00097 Event APRobotWaitingState::engageStatusCallback(const engagement_msgs::ActorIDStatus *msg) 00098 { 00099 this->debug(25, "Entered %s %s %s", 00100 engagement::RECOGNITION_NAMESPACE.c_str(), 00101 engagement::HUMAN_NAMESPACE.c_str(), 00102 engagement::RECOG_STATUS_TOPIC.c_str()); 00103 00104 // Make sure we have a valid message 00105 if (msg) 00106 { 00107 // Grab the message type from the constant pointer 00108 engagement_msgs::ActorIDStatus temp_msg = *msg; 00109 00110 // Cast ourselves into a state 00111 State *state = (State*)this; 00112 00113 // Grab the actor from the state 00114 Actor *actor = state->getActor(); 00115 00116 // Make sure the actor in the message is the same 00117 // and that the message flag is FALSE (unengaged) 00118 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00119 temp_msg.status.value == bml_msgs::Flag::FALSE) 00120 { 00121 // The actor for this recognizer has become unengaged 00122 // the connection event has failed. 00123 this->debug(7, "Received false %S message.", 00124 engagement::RECOG_STATUS_TOPIC.c_str()); 00125 00126 // Create the failure event 00127 return EventFactory::failed(); 00128 } 00129 } 00130 00131 return Event(); 00132 } 00133 00134 Event APRobotWaitingState::performingUtteranceCallback(const engagement_msgs::Speech *msg) 00135 { 00136 this->debug(25, "Entered %s %s", engagement::PERFORMING_NAMESPACE.c_str(), 00137 engagement::PERFORMING_UTTERANCE_TOPIC.c_str()); 00138 00139 // Make sure we have a valid message 00140 if (msg) 00141 { 00142 // Grab the message type from the constant pointer 00143 engagement_msgs::Speech temp_msg = *msg; 00144 00145 // Cast ourselves into a state 00146 State *state = (State*)this; 00147 00148 // Grab the actor from the state 00149 Actor *actor = state->getActor(); 00150 00151 // If this message relates to this actor, and is beginning 00152 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00153 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00154 { 00155 this->debug(7, "Received [%s] %s message.", 00156 temp_msg.actor.id.c_str(), 00157 engagement::PERFORMING_UTTERANCE_TOPIC.c_str()); 00158 00159 // Add the speech action used to succeed the event to the additional data 00160 std::vector<std::string> additional = std::vector<std::string>(); 00161 additional.push_back(Action::SPEECH); 00162 additional.push_back("determine what the human said"); 00163 00164 // Create the success event 00165 return EventFactory::success(additional); 00166 } 00167 else if (temp_msg.actor.id == temp_msg.actor.ROBOT && 00168 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00169 { 00170 this->debug(7, "Received ROBOT start %s message.", 00171 engagement::PERFORMING_UTTERANCE_TOPIC.c_str()); 00172 00173 // Create the robot initiated event 00174 return EventFactory::robotInitiated(); 00175 } 00176 else if (temp_msg.actor.id == temp_msg.actor.ROBOT && 00177 temp_msg.begin.value == bml_msgs::Flag::END && 00178 temp_msg.response.value == bml_msgs::Flag::OPTIONAL_RESPONSE) 00179 { 00180 this->debug(7, "Received ROBOT end %s message.", 00181 engagement::PERFORMING_UTTERANCE_TOPIC.c_str()); 00182 00183 // Create the failed event 00184 return EventFactory::failed(); 00185 } 00186 } 00187 00188 return Event(); 00189 } 00190 00191 Event APRobotWaitingState::visionShakeCallback(const engagement_msgs::Performance *msg) 00192 { 00193 this->debug(25, "Entered %s %s", engagement::VISION_NAMESPACE.c_str(), 00194 engagement::PERFORMING_SHAKE_TOPIC.c_str()); 00195 00196 // Make sure we have a valid message 00197 if (msg) 00198 { 00199 // Grab the message type from the constant pointer 00200 engagement_msgs::Performance temp_msg = *msg; 00201 00202 // Cast ourselves into a state 00203 State *state = (State*)this; 00204 00205 // Grab the actor from the state 00206 Actor *actor = state->getActor(); 00207 00208 // If this message relates to this actor, and is beginning 00209 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00210 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00211 { 00212 this->debug(7, "Received %s %s message.", 00213 engagement::VISION_NAMESPACE.c_str(), 00214 engagement::PERFORMING_SHAKE_TOPIC.c_str()); 00215 00216 // Add the shake action used to succeed the event to the additional data 00217 std::vector<std::string> additional = std::vector<std::string>(); 00218 additional.push_back(Action::SHAKE); 00219 00220 // Create the complete event 00221 return EventFactory::completed(additional); 00222 00223 } 00224 } 00225 00226 return Event(); 00227 } 00228 00229 Event APRobotWaitingState::visionNodCallback(const engagement_msgs::Performance *msg) 00230 { 00231 this->debug(25, "Entered %s %s", engagement::VISION_NAMESPACE.c_str(), 00232 engagement::PERFORMING_NOD_TOPIC.c_str()); 00233 00234 // Make sure we have a valid message 00235 if (msg) 00236 { 00237 // Grab the message type from the constant pointer 00238 engagement_msgs::Performance temp_msg = *msg; 00239 00240 // Cast ourselves into a state 00241 State *state = (State*)this; 00242 00243 // Grab the actor from the state 00244 Actor *actor = state->getActor(); 00245 00246 // If this message relates to this actor, and is beginning 00247 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00248 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00249 { 00250 this->debug(7, "Received %s %s message.", 00251 engagement::VISION_NAMESPACE.c_str(), 00252 engagement::PERFORMING_NOD_TOPIC.c_str()); 00253 00254 // Add the nod action used to succeed the event to the additional data 00255 std::vector<std::string> additional = std::vector<std::string>(); 00256 additional.push_back(Action::NOD); 00257 00258 // Create the complete event 00259 return EventFactory::completed(additional); 00260 } 00261 } 00262 00263 return Event(); 00264 } 00265 00266 Event APRobotWaitingState::visionExtendedActionCallback(const engagement_msgs::Performance *msg) 00267 { 00268 this->debug(25, "Entered %s %s", engagement::VISION_NAMESPACE.c_str(), 00269 engagement::PERFORMING_EXTENDED_ACTION_TOPIC.c_str()); 00270 00271 // Make sure we have a valid message 00272 if (msg) 00273 { 00274 // Grab the message type from the constant pointer 00275 engagement_msgs::Performance temp_msg = *msg; 00276 00277 // Cast ourselves into a state 00278 State *state = (State*)this; 00279 00280 // Grab the actor from the state 00281 Actor *actor = state->getActor(); 00282 00283 // If this message relates to this actor, and is beginning 00284 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00285 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00286 { 00287 this->debug(7, "Received %s %s message.", 00288 engagement::VISION_NAMESPACE.c_str(), 00289 engagement::PERFORMING_EXTENDED_ACTION_TOPIC.c_str()); 00290 00291 // Add the extended action used to succeed the event 00292 std::vector<std::string> additional = std::vector<std::string>(); 00293 additional.push_back(Action::EXTENDED_ACTION); 00294 00295 if (temp_msg.objects.size() > 0) 00296 additional.push_back(temp_msg.objects.at(0).id); 00297 00298 // Create the complete event 00299 return EventFactory::completed(additional); 00300 } 00301 } 00302 00303 return Event(); 00304 } 00305 00306 Event APRobotWaitingState::visionPointCallback(const engagement_msgs::Performance *msg) 00307 { 00308 this->debug(25, "Entered %s %s", engagement::VISION_NAMESPACE.c_str(), 00309 engagement::PERFORMING_POINT_TOPIC.c_str()); 00310 00311 // Make sure we have a valid message 00312 if (msg) 00313 { 00314 // Grab the message type from the constant pointer 00315 engagement_msgs::Performance temp_msg = *msg; 00316 00317 // Cast ourselves into a state 00318 State *state = (State*)this; 00319 00320 // Grab the actor from the state 00321 Actor *actor = state->getActor(); 00322 00323 // If this message relates to this actor, and is beginning 00324 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00325 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00326 { 00327 this->debug(7, "Received %s %s message.", 00328 engagement::VISION_NAMESPACE.c_str(), 00329 engagement::PERFORMING_POINT_TOPIC.c_str()); 00330 00331 // Add the point action used to succeed the event to the additional data 00332 std::vector<std::string> additional = std::vector<std::string>(); 00333 additional.push_back(Action::POINT); 00334 00335 if (temp_msg.objects.size() > 0) 00336 additional.push_back(temp_msg.objects.at(0).id); 00337 00338 // Create the completed event 00339 return EventFactory::completed(additional); 00340 } 00341 } 00342 00343 return Event(); 00344 } 00345 00346 Event APRobotWaitingState::visionLookCallback(const engagement_msgs::Performance *msg) 00347 { 00348 this->debug(25, "Entered %s %s", engagement::VISION_NAMESPACE.c_str(), 00349 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00350 00351 // Make sure we have a valid message 00352 if (msg) 00353 { 00354 // Grab the message type from the constant pointer 00355 engagement_msgs::Performance temp_msg = *msg; 00356 00357 // Cast ourselves into a state 00358 State *state = (State*)this; 00359 00360 // Grab the actor from the state 00361 Actor *actor = state->getActor(); 00362 00363 // If the message relates to this actor, and is beginning 00364 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00365 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00366 { 00367 this->debug(7, "Received %s %s message.", 00368 engagement::VISION_NAMESPACE.c_str(), 00369 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00370 00371 // Add the look action used to succeed the event to the additional data 00372 std::vector<std::string> additional = std::vector<std::string>(); 00373 additional.push_back(Action::LOOK); 00374 00375 if (temp_msg.objects.size() > 0) 00376 additional.push_back(temp_msg.objects.at(0).id); 00377 00378 // Issue a completed event 00379 return EventFactory::completed(additional); 00380 } 00381 } 00382 00383 return Event(); 00384 } 00385 00386 std::string APRobotWaitingState::type() 00387 { 00388 return "ap_robot_waiting"; 00389 } 00390 |