Project: engagement_recognition License: BSD Dependencies:
Used by:
None |
engagement_recognition/src/recognition/recognizers/mutual_facial_gaze/mfg_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 "mfg_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 MFGRobotWaitingState::MFGRobotWaitingState() : 00042 State(MFGRobotWaitingState::type(), "", NULL) 00043 { 00044 // Set the logger based on this type of recognizer 00045 this->setLogger(EngagementParams::getStateTag(MFGRobotWaitingState::type())); 00046 00047 this->warn("Initialized with an invalid actor, and EventSink."); 00048 } 00049 00050 MFGRobotWaitingState::MFGRobotWaitingState(std::string actor, EventSink *sink) : 00051 State(MFGRobotWaitingState::type(), actor, sink) 00052 { 00053 // Set the logger based on this type of recognizer 00054 this->setLogger(sink->getLogger(), 00055 EngagementParams::getStateTag(MFGRobotWaitingState::type())); 00056 } 00057 00058 MFGRobotWaitingState::~MFGRobotWaitingState() 00059 { 00060 } 00061 00062 Event MFGRobotWaitingState::received(std::string topic, 00063 engagement_msgs::ActorIDStatus *message) 00064 { 00065 if (topic == engagement::RECOGNITION_NAMESPACE + "/" + 00066 engagement::HUMAN_NAMESPACE + "/" + engagement::RECOG_STATUS_TOPIC) 00067 return this->engageStatusCallback(message); 00068 00069 return Event(); 00070 } 00071 00072 Event MFGRobotWaitingState::received(std::string topic, 00073 engagement_msgs::Performance *message) 00074 { 00075 if (topic == engagement::VISION_NAMESPACE + "/" + engagement::PERFORMING_FACIAL_GAZE_TOPIC) 00076 return this->visionFacialGazeCallback(message); 00077 else if (topic == engagement::VISION_NAMESPACE + "/" + engagement::PERFORMING_LOOK_TOPIC) 00078 return this->visionLookCallback(message); 00079 else if (topic == engagement::PERFORMING_NAMESPACE + "/" + engagement::PERFORMING_LOOK_TOPIC) 00080 return this->performingLookCallback(message); 00081 00082 return Event(); 00083 } 00084 00085 Event MFGRobotWaitingState::received(std::string topic, 00086 engagement_srvs::RobotDirectedGaze::Request *message) 00087 { 00088 if (topic == engagement::RECOGNITION_NAMESPACE + "/" + 00089 engagement::ROBOT_NAMESPACE + "/" + engagement::RECOG_DIRECTED_GAZE_TOPIC) 00090 return this->recogDirGazeCallback(message); 00091 00092 return Event(); 00093 } 00094 00095 Event MFGRobotWaitingState::engageStatusCallback(const engagement_msgs::ActorIDStatus *msg) 00096 { 00097 this->debug(25, "Entered %s %s %s", 00098 engagement::RECOGNITION_NAMESPACE.c_str(), 00099 engagement::HUMAN_NAMESPACE.c_str(), 00100 engagement::RECOG_STATUS_TOPIC.c_str()); 00101 00102 // Make sure we have a valid message 00103 if (msg) 00104 { 00105 // Grab the message type from the constant pointer 00106 engagement_msgs::ActorIDStatus temp_msg = *msg; 00107 00108 // Cast ourselves into a state 00109 State *state = (State*)this; 00110 00111 // Grab the actor from the state 00112 Actor *actor = state->getActor(); 00113 00114 // Make sure the actor in the message is the same 00115 // and that the message flag is FALSE (unengaged) 00116 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00117 temp_msg.status.value == bml_msgs::Flag::FALSE) 00118 { 00119 // The actor for this recognizer has become unengaged 00120 // the connection event has failed. 00121 this->debug(7, "Received false %s message.", 00122 engagement::RECOG_STATUS_TOPIC.c_str()); 00123 00124 // Create the failure event 00125 return EventFactory::failed(); 00126 } 00127 } 00128 00129 return Event(); 00130 } 00131 00132 Event MFGRobotWaitingState::performingLookCallback(const engagement_msgs::Performance *msg) 00133 { 00134 this->debug(25, "Entered %s %s", 00135 engagement::PERFORMING_NAMESPACE.c_str(), 00136 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00137 00138 // Make sure we have a valid message 00139 if (msg) 00140 { 00141 // Grab the message type from the constant pointer 00142 engagement_msgs::Performance temp_msg = *msg; 00143 00144 // Cast ourselves into a state 00145 State *state = (State*)this; 00146 00147 // Grab the actor from the state 00148 Actor *actor = state->getActor(); 00149 00150 // Make sure the message is beginning 00151 if (temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00152 { 00153 // If the robot begins looking at objects then we fail 00154 if (actor != NULL && objects::areObjects(temp_msg.objects) && 00155 temp_msg.actor.id == temp_msg.actor.ROBOT) 00156 { 00157 this->debug(7, "Received %s %s message.", 00158 engagement::PERFORMING_NAMESPACE.c_str(), 00159 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00160 00161 // Create the failure event 00162 return EventFactory::failed(); 00163 } 00164 } 00165 } 00166 00167 return Event(); 00168 } 00169 00170 Event MFGRobotWaitingState::recogDirGazeCallback(const engagement_srvs::RobotDirectedGaze::Request *msg) 00171 { 00172 this->debug(25, "Entered %s %s", 00173 engagement::RECOGNITION_NAMESPACE.c_str(), 00174 engagement::RECOG_DIRECTED_GAZE_TOPIC.c_str()); 00175 00176 // Make sure we have a valid message 00177 if (msg) 00178 { 00179 // Grab the message type from the constant pointer 00180 engagement_srvs::RobotDirectedGaze::Request temp_msg = *msg; 00181 00182 // So long as the instruction is to start directed gaze we fail 00183 if (temp_msg.done.value == bml_msgs::Flag::NOT_DONE) 00184 { 00185 this->debug(7, "Received %s %s message.", 00186 engagement::RECOGNITION_NAMESPACE.c_str(), 00187 engagement::RECOG_DIRECTED_GAZE_TOPIC.c_str()); 00188 00189 // Create the failure event 00190 return EventFactory::failed(); 00191 } 00192 } 00193 00194 return Event(); 00195 } 00196 00197 Event MFGRobotWaitingState::visionLookCallback(const engagement_msgs::Performance *msg) 00198 { 00199 this->debug(25, "Entered %s %s", 00200 engagement::VISION_NAMESPACE.c_str(), 00201 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00202 00203 // Make sure we have a valid message 00204 if (msg) 00205 { 00206 // Grab the message type from the constant pointer 00207 engagement_msgs::Performance temp_msg = *msg; 00208 00209 // Cast ourselves into a state 00210 State *state = (State*)this; 00211 00212 // Grab the actor from the state 00213 Actor *actor = state->getActor(); 00214 00215 // Make sure the message is beginning 00216 if (temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00217 { 00218 // If the actor begins looking at objects then we fail 00219 if (actor != NULL && objects::areObjects(temp_msg.objects) && 00220 temp_msg.actor.id != actor->getID()) 00221 { 00222 this->debug(7, "Received %s %s message.", 00223 engagement::VISION_NAMESPACE.c_str(), 00224 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00225 00226 // Create the failure event 00227 return EventFactory::failed(); 00228 } 00229 } 00230 } 00231 00232 return Event(); 00233 } 00234 00235 Event MFGRobotWaitingState::visionFacialGazeCallback(const engagement_msgs::Performance *msg) 00236 { 00237 this->debug(25, "Entered %s %s", 00238 engagement::VISION_NAMESPACE.c_str(), 00239 engagement::PERFORMING_FACIAL_GAZE_TOPIC.c_str()); 00240 00241 // Make sure we have a valid message 00242 if (msg) 00243 { 00244 // Grab the message type from the constant pointer 00245 engagement_msgs::Performance temp_msg = *msg; 00246 00247 // Cast ourselves into a State 00248 State *state = (State*)this; 00249 00250 // Grab the actor from the state 00251 Actor *actor = state->getActor(); 00252 00253 // If the actor begins making facial gaze with the robot we succeed 00254 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00255 temp_msg.begin.value == bml_msgs::Flag::BEGIN && 00256 objects::isFace(temp_msg.objects, temp_msg.actor.ROBOT)) 00257 { 00258 this->debug(7, "Received %s %s message.", 00259 engagement::VISION_NAMESPACE.c_str(), 00260 engagement::PERFORMING_FACIAL_GAZE_TOPIC.c_str()); 00261 00262 // Create the shared event 00263 return EventFactory::sharedGaze(); 00264 } 00265 } 00266 00267 return Event(); 00268 } 00269 00270 std::string MFGRobotWaitingState::type() 00271 { 00272 return "mfg_robot_waiting"; 00273 } |