Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008 #include <tk_behavior/BehaviorInterface.hpp>
00009
00010 #include <tk_behavior/Behavior.hpp>
00011
00012 namespace TELEKYB_NAMESPACE {
00013
00014 BehaviorInterface::BehaviorInterface(Behavior& behavior_)
00015 : behavior(behavior_), nodeHandle(behavior.getNodeHandle())
00016 {
00017 setNextBehavior = nodeHandle.advertiseService(
00018 BEHAVIOR_SETNEXTBEHAVIOR, &BehaviorInterface::setNextBehaviorCB , this);
00019 getNextBehavior = nodeHandle.advertiseService(
00020 BEHAVIOR_GETNEXTBEHAVIOR, &BehaviorInterface::getNextBehaviorCB , this);
00021 setParameterInitialized = nodeHandle.advertiseService(
00022 BEHAVIOR_SETPARAMINIT, &BehaviorInterface::setParameterInitializedCB , this);
00023
00024 }
00025
00026 BehaviorInterface::~BehaviorInterface()
00027 {
00028
00029 }
00030
00031
00032
00033 bool BehaviorInterface::setNextBehaviorCB(
00034 telekyb_srvs::BehaviorInput::Request& request,
00035 telekyb_srvs::BehaviorInput::Response& response)
00036 {
00037 return behavior.setNextBehavior( Behavior::behaviorFromID(request.behaviorID) );
00038 }
00039
00040 bool BehaviorInterface::getNextBehaviorCB(
00041 telekyb_srvs::BehaviorOutput::Request& request,
00042 telekyb_srvs::BehaviorOutput::Response& response)
00043 {
00044
00045 Behavior* b = behavior.getNextBehavior();
00046 response.behaviorID = b->getID();
00047 response.behaviorName = b->getName();
00048 return true;
00049 }
00050
00051 bool BehaviorInterface::setParameterInitializedCB(
00052 telekyb_srvs::BoolInput::Request& request,
00053 telekyb_srvs::BoolInput::Response& response)
00054 {
00055 behavior.setParameterInitialized((bool)request.input);
00056 return true;
00057 }
00058
00059 }