Project: engagement_recognition License: BSD Dependencies:
Used by:
None |
engagement_recognition/src/recognition/recognizers/mutual_facial_gaze/mfg_mutual_facial_gaze_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 "mfg_mutual_facial_gaze_state.h" 00036 00037 #include "../../events/event_factory.h" 00038 #include "../../lib/engagement_params.h" 00039 #include "../../objects/engagement_objects.h" 00040 00041 MFGMutualFacialGazeState::MFGMutualFacialGazeState() : 00042 State(MFGMutualFacialGazeState::type(), "", NULL) 00043 { 00044 // Set the logger based on this type of recognizer 00045 this->setLogger(EngagementParams::getStateTag( 00046 MFGMutualFacialGazeState::type())); 00047 00048 this->warn("Initialized with an invalid actor, and EventSink."); 00049 } 00050 00051 MFGMutualFacialGazeState::MFGMutualFacialGazeState(std::string actor, 00052 EventSink *sink) : 00053 State(MFGMutualFacialGazeState::type(), actor, sink) 00054 { 00055 // Set the logger based on this type of recognizer 00056 this->setLogger(sink->getLogger(), 00057 EngagementParams::getStateTag(MFGMutualFacialGazeState::type())); 00058 00059 if (actor == "") 00060 this->warn("Initialized with an invalid actor."); 00061 } 00062 00063 MFGMutualFacialGazeState::~MFGMutualFacialGazeState() 00064 { 00065 } 00066 00067 Event MFGMutualFacialGazeState::received(std::string topic, 00068 engagement_srvs::RobotMutualFacialGaze::Request *message) 00069 { 00070 if (topic == engagement::RECOGNITION_NAMESPACE + "/" + 00071 engagement::ROBOT_NAMESPACE + "/" + engagement::RECOG_MUTUAL_FACIAL_GAZE_TOPIC) 00072 return this->recogMFGazeCallback(message); 00073 00074 return Event(); 00075 } 00076 00077 Event MFGMutualFacialGazeState::received(std::string topic, 00078 engagement_msgs::ActorIDStatus *message) 00079 { 00080 if (topic == engagement::RECOGNITION_NAMESPACE + "/" + 00081 engagement::HUMAN_NAMESPACE + "/" + 00082 engagement::RECOG_STATUS_TOPIC.c_str()) 00083 return this->engageStatusCallback(message); 00084 00085 return Event(); 00086 } 00087 00088 Event MFGMutualFacialGazeState::received(std::string topic, 00089 engagement_msgs::Performance *message) 00090 { 00091 if (topic == engagement::VISION_NAMESPACE + "/" + engagement::PERFORMING_FACIAL_GAZE_TOPIC) 00092 return this->visionFacialGazeCallback(message); 00093 else if (topic == engagement::PERFORMING_NAMESPACE + "/" + engagement::PERFORMING_LOOK_TOPIC) 00094 return this->performingLookCallback(message); 00095 else if (topic == engagement::VISION_NAMESPACE + "/" + engagement::PERFORMING_LOOK_TOPIC) 00096 return this->visionLookCallback(message); 00097 00098 return Event(); 00099 } 00100 00101 Event MFGMutualFacialGazeState::received(std::string topic, 00102 engagement_srvs::RobotDirectedGaze::Request *message) 00103 { 00104 if (topic == engagement::RECOGNITION_NAMESPACE + 00105 engagement::ROBOT_NAMESPACE + "/" + "/" + engagement::RECOG_DIRECTED_GAZE_TOPIC) 00106 return this->recogDirGazeCallback(message); 00107 00108 return Event(); 00109 } 00110 00111 Event MFGMutualFacialGazeState::performingLookCallback(const engagement_msgs::Performance *msg) 00112 { 00113 this->debug(25, "Entered %s %s", 00114 engagement::PERFORMING_NAMESPACE.c_str(), 00115 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00116 00117 // Make sure we have a valid message 00118 if (msg) 00119 { 00120 // Grab the message type from the constant pointer 00121 engagement_msgs::Performance temp_msg = *msg; 00122 00123 // Cast ourselves into a state 00124 State *state = (State*)this; 00125 00126 // Grab the actor from the state 00127 Actor *actor = state->getActor(); 00128 00129 // If this relates to a the same actor, and it's beginning 00130 if (actor != NULL && temp_msg.actor.id == temp_msg.actor.ROBOT && 00131 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00132 { 00133 this->debug(7, "Received %s %s message.", 00134 engagement::PERFORMING_NAMESPACE.c_str(), 00135 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00136 00137 // A connection event completed successfully 00138 return EventFactory::completed(); 00139 } 00140 } 00141 00142 return Event(); 00143 } 00144 00145 Event MFGMutualFacialGazeState::recogMFGazeCallback(const engagement_srvs::RobotMutualFacialGaze::Request *msg) 00146 { 00147 this->debug(25, "Entered %s %s", 00148 engagement::RECOGNITION_NAMESPACE.c_str(), 00149 engagement::RECOG_MUTUAL_FACIAL_GAZE_TOPIC.c_str()); 00150 00151 // Make sure we have a valid message 00152 if (msg) 00153 { 00154 // Grab the message type from the constant pointer 00155 engagement_srvs::RobotMutualFacialGaze::Request temp_msg = *msg; 00156 00157 // Cast ourselves into a state 00158 State *state = (State*)this; 00159 00160 // Grab the actor from the state 00161 Actor *actor = state->getActor(); 00162 00163 // if the actor is different 00164 if (actor != NULL && temp_msg.actor.id != actor->getID()) 00165 { 00166 // We are ending facial gaze with the same actor 00167 this->debug(7, "Received %s %s message.", 00168 engagement::RECOGNITION_NAMESPACE.c_str(), 00169 engagement::RECOG_MUTUAL_FACIAL_GAZE_TOPIC.c_str()); 00170 00171 // A connection event completed successfully 00172 return EventFactory::completed(); 00173 } 00174 else if (actor != NULL && temp_msg.actor.id == actor->getID()) 00175 { 00176 this->debug(7, "Received restart %s %s message.", 00177 engagement::RECOGNITION_NAMESPACE.c_str(), 00178 engagement::RECOG_MUTUAL_FACIAL_GAZE_TOPIC.c_str()); 00179 00180 // Create a shared gaze event 00181 return EventFactory::sharedGaze(); 00182 } 00183 } 00184 00185 return Event(); 00186 } 00187 00188 Event MFGMutualFacialGazeState::recogDirGazeCallback(const engagement_srvs::RobotDirectedGaze::Request *msg) 00189 { 00190 this->debug(25, "Entered %s %s", 00191 engagement::RECOGNITION_NAMESPACE.c_str(), 00192 engagement::RECOG_DIRECTED_GAZE_TOPIC.c_str()); 00193 00194 // Make sure we have a valid message 00195 if (msg) 00196 { 00197 // Grab the message type from the constant pointer 00198 engagement_srvs::RobotDirectedGaze::Request temp_msg = *msg; 00199 00200 // As long as this message is NOT DONE 00201 if (temp_msg.done.value == bml_msgs::Flag::NOT_DONE) 00202 { 00203 this->debug(7, "Received Begin %s %s message.", 00204 engagement::RECOGNITION_NAMESPACE.c_str(), 00205 engagement::RECOG_DIRECTED_GAZE_TOPIC.c_str()); 00206 00207 // A connection event completed successfully 00208 return EventFactory::completed(); 00209 } 00210 } 00211 00212 return Event(); 00213 } 00214 00215 Event MFGMutualFacialGazeState::visionLookCallback(const engagement_msgs::Performance *msg) 00216 { 00217 this->debug(25, "Entered %s %s", 00218 engagement::VISION_NAMESPACE.c_str(), 00219 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00220 00221 // Make sure we have a valid message 00222 if (msg) 00223 { 00224 // Grab the message type from the constant pointer 00225 engagement_msgs::Performance temp_msg = *msg; 00226 00227 // Cast ourselves into a state 00228 State *state = (State*)this; 00229 00230 // Grab the actor from the state 00231 Actor *actor = state->getActor(); 00232 00233 // Make sure this message relates to the actor for this recognizer 00234 // and that the look is starting 00235 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00236 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00237 { 00238 this->debug(7, "Received Begin %s %s message.", 00239 engagement::VISION_NAMESPACE.c_str(), 00240 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00241 00242 // Create a success event 00243 return EventFactory::completed(); 00244 } 00245 } 00246 00247 return Event(); 00248 } 00249 00250 Event MFGMutualFacialGazeState::visionFacialGazeCallback(const engagement_msgs::Performance *msg) 00251 { 00252 this->debug(25, "Entered %s %s", 00253 engagement::VISION_NAMESPACE.c_str(), 00254 engagement::PERFORMING_FACIAL_GAZE_TOPIC.c_str()); 00255 00256 // Make sure we have a valid message 00257 if (msg) 00258 { 00259 // Grab the message type from the constant pointer 00260 engagement_msgs::Performance temp_msg = *msg; 00261 00262 // Cast ourselves into a state 00263 State *state = (State*)this; 00264 00265 // Grab the actor from the state 00266 Actor *actor = state->getActor(); 00267 00268 // Make sure this message relates to the actor for this recognizer 00269 // and that the facial gaze is ending 00270 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00271 temp_msg.begin.value == bml_msgs::Flag::END && 00272 objects::isFace(temp_msg.objects, temp_msg.actor.ROBOT)) 00273 { 00274 this->debug(7, "Received End %s %s message.", 00275 engagement::VISION_NAMESPACE.c_str(), 00276 engagement::PERFORMING_FACIAL_GAZE_TOPIC.c_str()); 00277 00278 // Create a success event 00279 return EventFactory::completed(); 00280 } 00281 } 00282 00283 return Event(); 00284 } 00285 00286 Event MFGMutualFacialGazeState::engageStatusCallback(const engagement_msgs::ActorIDStatus *msg) 00287 { 00288 this->debug(25, "Entered %s %s %s", 00289 engagement::RECOGNITION_NAMESPACE.c_str(), 00290 engagement::HUMAN_NAMESPACE.c_str(), 00291 engagement::RECOG_STATUS_TOPIC.c_str()); 00292 00293 // Make sure we have a valid message 00294 if (msg) 00295 { 00296 // Grab the message type from the constant pointer 00297 engagement_msgs::ActorIDStatus temp_msg = *msg; 00298 00299 // Cast ourselves into a state 00300 State *state = (State*)this; 00301 00302 // Grab the actor from the state 00303 Actor *actor = state->getActor(); 00304 00305 // Make sure this message relates to the actor for this recognizer 00306 // and that the flag is FALSE 00307 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00308 temp_msg.status.value == bml_msgs::Flag::FALSE) 00309 { 00310 this->debug(7, "Received false %s message.", 00311 engagement::RECOG_STATUS_TOPIC.c_str()); 00312 00313 // Create a success event 00314 return EventFactory::completed(); 00315 } 00316 } 00317 00318 return Event(); 00319 } 00320 00321 std::string MFGMutualFacialGazeState::type() 00322 { 00323 return "mfg_mutual_facial_gaze"; 00324 } 00325 |