Project: engagement_recognition License: BSD Dependencies:
Used by:
None |
engagement_recognition/src/recognition/recognizers/mutual_facial_gaze/mutual_facial_gaze_recognizer.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 "mutual_facial_gaze_recognizer.h" 00036 00037 #include "../../events/event_factory.h" 00038 #include "../../lib/engagement_params.h" 00039 #include "../../lib/engagement_macros.h" 00040 00041 MutualFacialGazeRecognizer::MutualFacialGazeRecognizer(): 00042 Recognizer(MutualFacialGazeRecognizer::type(), NULL) 00043 { 00044 // Set the logger based on this type of recognizer 00045 this->setLogger(EngagementParams::getMFGTag()); 00046 00047 // Load the max delay parameter 00048 this->getMaxDelayParam(EngagementParams::getConfMFGazeHandle(), 2.0); 00049 00050 // Create the start state, and set the state to it 00051 this->setStartState(); 00052 00053 // Grab the recognition/human NodeHandle 00054 ros::NodeHandle *recog_human = EngagementParams::getRecogHumanHandle(); 00055 00056 // Advertise the human initiated topic 00057 hi_mf_gaze_pub_ = recog_human->advertise<engagement_msgs::HumanMutualFacialGaze>( 00058 engagement::RECOG_MUTUAL_FACIAL_GAZE_TOPIC, MAX_BUFFER); 00059 00060 this->warn("Initialized recognizer to an empty actor."); 00061 } 00062 00063 MutualFacialGazeRecognizer::MutualFacialGazeRecognizer(std::string actor, 00064 EventSink *sink): 00065 Recognizer(MutualFacialGazeRecognizer::type(), sink) 00066 { 00067 // Set the logger based on this type of recognizer 00068 this->setLogger(sink->getLogger(), EngagementParams::getMFGTag()); 00069 00070 // Load the max delay parameter 00071 this->getMaxDelayParam(EngagementParams::getConfMFGazeHandle(), 2.0); 00072 00073 // Set the actor for this recognizer 00074 // Do this BEFORE setting the state 00075 setActor(actor); 00076 00077 // Grab the recognition/human NodeHandle 00078 ros::NodeHandle *recog_human = EngagementParams::getRecogHumanHandle(); 00079 00080 // Advertise the human initiated topic 00081 hi_mf_gaze_pub_ = recog_human->advertise<engagement_msgs::HumanMutualFacialGaze>( 00082 engagement::RECOG_MUTUAL_FACIAL_GAZE_TOPIC, MAX_BUFFER); 00083 00084 // Create the start state and set the state to it 00085 this->setStartState(); 00086 } 00087 00088 void MutualFacialGazeRecognizer::initialize(initiator::Initiator initiator) 00089 { 00090 Recognizer *rec = (Recognizer*)this; 00091 00092 // If the human was the initiator, send a human initiated message 00093 if (initiator == initiator::HUMAN) 00094 { 00095 // Grab the internal node handle 00096 ros::NodeHandle *n = EngagementParams::getConfMFGazeHandle(); 00097 00098 // Grab the max delay from the parameter server 00099 double max_delay = this->getMaxDelayParam(n, 2.0); 00100 00101 // Only send human initiated events if the recognizer is not degraded 00102 if (!EngagementParams::isDegraded()) 00103 { 00104 // Create the human initiated mutual facial gaze message 00105 engagement_msgs::HumanMutualFacialGaze mfg_msg; 00106 00107 // Set the actor, the timeout duration, and the 00108 // human's utterance for this message 00109 mfg_msg.actor.id = this->getActor()->getID(); 00110 mfg_msg.timeout = max_delay; 00111 00112 this->debug(5, "Publishing human initiated event."); 00113 // Publish the message 00114 this->hi_mf_gaze_pub_.publish(mfg_msg); 00115 } 00116 } 00117 00118 // Initialize this recognizer with the initiator 00119 rec->initialize(initiator); 00120 } 00121 00122 void MutualFacialGazeRecognizer::transition(Event event) 00123 { 00124 // Grab the additional vector from the event 00125 std::vector<std::string> event_additional = event.getAdditional(); 00126 00127 // Check the event cases 00128 if (EventFactory::isRobotInitiated(event)) 00129 { 00130 this->debug(8, "ROBOT INITIATED EVENT."); 00131 00132 // Unblock the semaphore and enter the robot waiting state 00133 this->unblock(ServiceResponse::cycle(), Action::noAction()); 00134 this->setState(factory::MFG_ROBOT_WAITING); 00135 00136 // Initialize the connection event 00137 this->initialize(initiator::ROBOT); 00138 this->start_delay_ = CURRENT_TIME; 00139 } 00140 else if (EventFactory::isHumanInitiated(event)) 00141 { 00142 this->debug(8, "HUMAN INITIATED EVENT."); 00143 00144 // Unblock the semaphore and enter the human waiting state 00145 this->unblock(ServiceResponse::cycle(), Action::noAction()); 00146 this->setState(factory::MFG_HUMAN_WAITING); 00147 00148 // Initialize the connection event 00149 this->initialize(initiator::HUMAN); 00150 this->start_delay_ = CURRENT_TIME; 00151 } 00152 else if (EventFactory::isSharedGaze(event)) 00153 { 00154 this->debug(8, "SHARED GAZE EVENT."); 00155 00156 // If we're currently in the start state 00157 if (this->getStateName() != StateFactory::getType(factory::MFG_START)) 00158 { 00159 // If we were given an initiator, set it (should be the first element) 00160 if (event_additional.size() == 1) 00161 { 00162 // Initialize the recognizer, with human or robot accordingly 00163 this->initialize((event_additional.at(0) == "ROBOT" 00164 ? initiator::ROBOT : initiator::HUMAN)); 00165 } 00166 } 00167 else if (this->getStateName() == StateFactory::getType(factory::MFG_START)) 00168 { 00169 // Set the start delay time to now, since there should be no delay 00170 this->start_time_ = CURRENT_TIME; 00171 this->start_delay_ = this->start_time_; 00172 } 00173 00174 // Enter the mutual facial gaze state 00175 this->setState(factory::MFG_MUTUAL_FACIAL_GAZE); 00176 00177 this->end_delay_ = CURRENT_TIME; 00178 00179 // We succeed in this case (look always succeeds MFG) 00180 this->succeed(Action::look()); 00181 } 00182 else if (EventFactory::isCompleted(event)) 00183 { 00184 this->debug(8, "COMPLETED EVENT."); 00185 00186 // Move to the start state 00187 this->setStartState(); 00188 00189 // Complete the connection event successfully 00190 this->complete(true); 00191 } 00192 else if (EventFactory::isFailed(event)) 00193 { 00194 this->debug(8, "FAILED EVENT."); 00195 00196 // Move to the start state 00197 this->setStartState(); 00198 00199 // Complete the connection event unsuccessfully 00200 this->complete(false); 00201 } 00202 } 00203 00204 std::string MutualFacialGazeRecognizer::type() 00205 { 00206 return engagement::MUTUAL_FACIAL_GAZE_TYPE; 00207 } |