Project: engagement_recognition License: BSD Dependencies:
Used by:
None |
engagement_recognition/src/recognition/recognizers/directed_gaze/dg_robot_directing_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 "dg_robot_directing_state.h" 00036 00037 #include "../../events/event_factory.h" 00038 #include "../../lib/engagement_params.h" 00039 #include "../../objects/engagement_objects.h" 00040 00041 DGRobotDirectingState::DGRobotDirectingState(): 00042 State(DGRobotDirectingState::type(), "", NULL) 00043 { 00044 // Set the logger based on this type of recognizer 00045 this->setLogger(EngagementParams::getStateTag(DGRobotDirectingState::type())); 00046 00047 this->warn("Initialized with an invalid actor, and EventSink."); 00048 } 00049 00050 DGRobotDirectingState::DGRobotDirectingState(std::string actor, EventSink *sink): 00051 State(DGRobotDirectingState::type(), actor, sink) 00052 { 00053 // Set the logger based on this type of recognizer 00054 this->setLogger(sink->getLogger(), 00055 EngagementParams::getStateTag(DGRobotDirectingState::type())); 00056 } 00057 00058 DGRobotDirectingState::~DGRobotDirectingState() 00059 { 00060 } 00061 00062 Event DGRobotDirectingState::received(std::string topic, 00063 engagement_srvs::RobotMutualFacialGaze::Request *message) 00064 { 00065 if (topic == engagement::RECOGNITION_NAMESPACE + "/" + 00066 engagement::ROBOT_NAMESPACE + "/" + engagement::RECOG_MUTUAL_FACIAL_GAZE_TOPIC) 00067 return this->recogMFGazeCallback(message); 00068 00069 return Event(); 00070 } 00071 00072 Event DGRobotDirectingState::received(std::string topic, 00073 engagement_msgs::ActorIDStatus *message) 00074 { 00075 if (topic == engagement::RECOGNITION_NAMESPACE + "/" + 00076 engagement::HUMAN_NAMESPACE + "/" + 00077 engagement::RECOG_STATUS_TOPIC.c_str()) 00078 return this->engageStatusCallback(message); 00079 00080 return Event(); 00081 } 00082 00083 Event DGRobotDirectingState::received(std::string topic, 00084 engagement_msgs::Performance *message) 00085 { 00086 if (topic == engagement::PERFORMING_NAMESPACE + "/" + engagement::PERFORMING_LOOK_TOPIC) 00087 return this->performingLookCallback(message); 00088 else if (topic == engagement::VISION_NAMESPACE + "/" + engagement::PERFORMING_LOOK_TOPIC) 00089 return this->visionLookCallback(message); 00090 else if (topic == engagement::VISION_NAMESPACE + "/" + engagement::PERFORMING_POINT_TOPIC) 00091 return this->visionPointCallback(message); 00092 00093 return Event(); 00094 } 00095 00103 Event DGRobotDirectingState::received(std::string topic, 00104 engagement_srvs::RobotDirectedGaze::Request *message) 00105 { 00106 if (topic == engagement::RECOGNITION_NAMESPACE + "/" + 00107 engagement::ROBOT_NAMESPACE + "/" + engagement::RECOG_DIRECTED_GAZE_TOPIC) 00108 return this->recogDirGazeCallback(message); 00109 00110 return Event(); 00111 } 00112 00113 Event DGRobotDirectingState::engageStatusCallback(const engagement_msgs::ActorIDStatus *msg) 00114 { 00115 this->debug(25, "Entered %s %s %s", 00116 engagement::RECOGNITION_NAMESPACE.c_str(), 00117 engagement::HUMAN_NAMESPACE.c_str(), 00118 engagement::RECOG_STATUS_TOPIC.c_str()); 00119 00120 // Make sure we have a valid message 00121 if (msg) 00122 { 00123 // Grab the message type from the constant pointer 00124 engagement_msgs::ActorIDStatus temp_msg = *msg; 00125 00126 // Cast ourselves into a state 00127 State *state = (State*)this; 00128 00129 // Grab the actor from the state 00130 Actor *actor = state->getActor(); 00131 00132 // Make sure the actor in the message is the same 00133 // and that the message flag is FALSE (unengaged) 00134 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00135 temp_msg.status.value == bml_msgs::Flag::FALSE) 00136 { 00137 // The actor for this recognizer has become unengaged 00138 // the connection event has failed. 00139 this->debug(7, "Received false %s message.", 00140 engagement::RECOG_STATUS_TOPIC.c_str()); 00141 00142 // Create the failure event 00143 return EventFactory::failed(); 00144 } 00145 } 00146 00147 return Event(); 00148 } 00149 00150 Event DGRobotDirectingState::performingLookCallback(const engagement_msgs::Performance *msg) 00151 { 00152 this->debug(25, "Entered %s %s", 00153 engagement::PERFORMING_NAMESPACE.c_str(), 00154 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00155 00156 // Make sure we have a valid message 00157 if (msg) 00158 { 00159 // Grab the message type from the constant pointer 00160 engagement_msgs::Performance temp_msg = *msg; 00161 00162 // Grab the objects from the entities in the message 00163 std::vector<std::string> objects = 00164 objects::getObjectsFromEntities(temp_msg.objects); 00165 00166 // Make sure the message done field is BEGIN (begin look) 00167 // and that the objects being intersect the objects we're looking at 00168 if (temp_msg.actor.id == temp_msg.actor.ROBOT && 00169 objects::areObjects(temp_msg.objects) && 00170 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00171 { 00172 // Failure is contingent upon whether or not the objects are different 00173 if (!this->compareAdditional(objects, EventSink::CONTAINS)) 00174 { 00175 this->debug(7, "Received %s %s message.", 00176 engagement::PERFORMING_NAMESPACE.c_str(), 00177 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00178 00179 // Create the failure event 00180 return EventFactory::failed(); 00181 } 00182 } 00183 } 00184 00185 return Event(); 00186 } 00187 00188 Event DGRobotDirectingState::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 // Cast ourselves into a State 00201 State *state = (State*)this; 00202 00203 // Grab the actor from the state 00204 Actor *actor = state->getActor(); 00205 00206 // Make sure the actors are NOT the same and that the message FLAG is TRUE 00207 // and that the objects being deleted intersects the 00208 // objects we're looking at 00209 if (actor != NULL && temp_msg.actor.id != actor->getID()) 00210 { 00211 this->debug(7, "Received %s %s message.", 00212 engagement::RECOGNITION_NAMESPACE.c_str(), 00213 engagement::RECOG_DIRECTED_GAZE_TOPIC.c_str()); 00214 00215 // Create the robot initiated event 00216 return EventFactory::robotInitiated(); 00217 } 00218 } 00219 00220 return Event(); 00221 } 00222 00223 Event DGRobotDirectingState::recogMFGazeCallback(const engagement_srvs::RobotMutualFacialGaze::Request *msg) 00224 { 00225 this->debug(25, "Entered %s %s", 00226 engagement::RECOGNITION_NAMESPACE.c_str(), 00227 engagement::RECOG_MUTUAL_FACIAL_GAZE_TOPIC.c_str()); 00228 00229 // Make sure we have a valid message 00230 if (msg) 00231 { 00232 // Grab the message type from the constant pointer 00233 engagement_srvs::RobotMutualFacialGaze::Request temp_msg = *msg; 00234 00235 // Cast ourselves into a State 00236 State *state = (State*)this; 00237 00238 // Grab the actor from the state 00239 Actor *actor = state->getActor(); 00240 00241 // Make sure the actors are NOT the same and that the objects being 00242 // deleted intersects the objects we're looking at 00243 if (actor != NULL && temp_msg.actor.id != actor->getID()) 00244 { 00245 // Now, we only fail if the robot is NOT pointing at the same objects 00246 // Compare the pointing for BOTH arms 00247 if (!this->compareAdditional(Robot::getPointing(), EventSink::CONTAINS)) 00248 { 00249 this->debug(7, "Received %s %s message", 00250 engagement::RECOGNITION_NAMESPACE.c_str(), 00251 engagement::RECOG_MUTUAL_FACIAL_GAZE_TOPIC.c_str()); 00252 00253 // Create the failure event 00254 return EventFactory::failed(); 00255 } 00256 } 00257 } 00258 00259 return Event(); 00260 } 00261 00262 Event DGRobotDirectingState::visionLookCallback(const engagement_msgs::Performance *msg) 00263 { 00264 this->debug(25, "Entered %s %s", 00265 engagement::VISION_NAMESPACE.c_str(), 00266 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00267 00268 // Make sure we have a valid message 00269 if (msg) 00270 { 00271 // Grab the message type from the constant pointer 00272 engagement_msgs::Performance temp_msg = *msg; 00273 00274 // Cast ourselves into a State 00275 State *state = (State*)this; 00276 00277 // Grab the actor from the state 00278 Actor *actor = state->getActor(); 00279 std::vector<std::string> objects = 00280 objects::getObjectsFromEntities(temp_msg.objects); 00281 00282 // Make sure the actors are the same and that the begin 00283 // flag is BEGIN (begin look) 00284 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00285 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00286 { 00287 // Actor is starting to look, only change if the objects are the same 00288 if (this->compareAdditional(objects, EventSink::CONTAINS)) 00289 { 00290 this->debug(7, "Received %s %s message.", 00291 engagement::VISION_NAMESPACE.c_str(), 00292 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00293 00294 // Create the shared gaze event 00295 return EventFactory::sharedGaze(); 00296 } 00297 else 00298 { 00299 this->debug(7, "Received %s %s message.", 00300 engagement::VISION_NAMESPACE.c_str(), 00301 engagement::PERFORMING_LOOK_TOPIC.c_str()); 00302 00303 // Create the shared gaze event 00304 return EventFactory::humanInitiated(); 00305 } 00306 } 00307 } 00308 00309 return Event(); 00310 } 00311 00312 Event DGRobotDirectingState::visionPointCallback(const engagement_msgs::Performance *msg) 00313 { 00314 this->debug(25, "Entered %s %s", 00315 engagement::VISION_NAMESPACE.c_str(), 00316 engagement::PERFORMING_POINT_TOPIC.c_str()); 00317 00318 // Make sure we have a valid message 00319 if (msg) 00320 { 00321 // Grab the message type from the constant pointer 00322 engagement_msgs::Performance temp_msg = *msg; 00323 00324 // Cast ourselves into a State 00325 State *state = (State*)this; 00326 00327 // Grab the actor from the state 00328 Actor *actor = state->getActor(); 00329 std::vector<std::string> objects = 00330 objects::getObjectsFromEntities(temp_msg.objects); 00331 00332 // Make sure the actors are the same and that the begin 00333 // flag is BEGIN (begin point) 00334 if (actor != NULL && temp_msg.actor.id == actor->getID() && 00335 temp_msg.begin.value == bml_msgs::Flag::BEGIN) 00336 { 00337 // Actor is starting to point, we only change state in the event that 00338 // the objects are different 00339 if (!this->compareAdditional(objects, EventSink::CONTAINS)) 00340 { 00341 this->debug(7, "Received %s %s message.", 00342 engagement::VISION_NAMESPACE.c_str(), 00343 engagement::PERFORMING_POINT_TOPIC.c_str()); 00344 00345 // Actor is looking at different objects. Move to human initiated 00346 return EventFactory::humanInitiated(); 00347 } 00348 } 00349 } 00350 00351 return Event(); 00352 } 00353 00354 std::string DGRobotDirectingState::type() 00355 { 00356 return "dg_robot_directing"; 00357 } |