Behavior.cpp
Go to the documentation of this file.
00001 /*
00002  * Behavior.cpp
00003  *
00004  *  Created on: Nov 10, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #include <tk_behavior/Behavior.hpp>
00009 
00010 #include <tk_behavior/BehaviorController.hpp>
00011 
00012 #include <boost/lexical_cast.hpp>
00013 
00014 #include <tk_behavior/BehaviorHelper.hpp>
00015 
00016 // For printing
00017 #define __STDC_FORMAT_MACROS
00018 #include <inttypes.h>
00019 
00020 namespace TELEKYB_NAMESPACE
00021 {
00022 
00023 Behavior::Behavior(const std::string& name_, const BehaviorType& type_)
00024         : OptionContainer( name_ + "/" + getIDString() ),
00025           type( type_ ),
00026           bController( BehaviorController::Instance() ),
00027           nodeHandle( bController.getBehaviorNodeHandle(), getIDString()),
00028           name( name_ ),
00029           parameterInitialized( false ),
00030           nextBehavior( NULL ),
00031           behaviorInterface ( NULL )
00032 {
00033         behaviorInterface = new BehaviorInterface(*this);
00034         ROS_DEBUG("Creating Behavior ID: %" PRIu64 " Name: %s", getID(), getName().c_str());
00035 }
00036 
00037 Behavior::~Behavior()
00038 {
00039         ROS_DEBUG("Deleting Behavior ID: %" PRIu64 " Name: %s", getID(), getName().c_str());
00040         delete behaviorInterface;
00041 }
00042 
00043 uint64_t Behavior::getID() const
00044 {
00045         return (uint64_t)this;
00046 }
00047 
00048 std::string Behavior::getIDString() const
00049 {
00050         return boost::lexical_cast<std::string>(getID());
00051 }
00052 
00053 bool Behavior::isParameterInitialized() const
00054 {
00055         return parameterInitialized;
00056 }
00057 
00058 void Behavior::setParameterInitialized(bool parameterInitialized_)
00059 {
00060         parameterInitialized = parameterInitialized_;
00061 }
00062 
00063 const ros::NodeHandle& Behavior::getNodeHandle() const
00064 {
00065         return nodeHandle;
00066 }
00067 
00068 //void Behavior::setName(const std::string& name_)
00069 //{
00070 //      name = name_;
00071 //}
00072 
00073 std::string Behavior::getName() const
00074 {
00075         return name;
00076 };
00077 
00078 bool Behavior::isActive() const
00079 {
00080         return (bController.getActiveBehavior() == this);
00081 }
00082 
00083 bool Behavior::setNextBehavior(Behavior* nextBehavior_)
00084 {
00085         // should we allow to set oneself as next Behavior. I think yes! :)
00086 
00087         // validity check
00088         if ( !exists(nextBehavior_) ) {
00089                 ROS_ERROR_STREAM("Trying to set nextBehavior of " << getName() << " to an invalid BehaviorInstance!");
00090                 return false;
00091         }
00092 
00093         nextBehavior = nextBehavior_;
00094         return true;
00095 }
00096 
00097 void Behavior::unsetNextBehavior()
00098 {
00099         nextBehavior = NULL;
00100 }
00101 
00102 bool Behavior::hasNextBehavior() const
00103 {
00104         return (nextBehavior != NULL);
00105 }
00106 
00107 Behavior* Behavior::getNextBehavior() const
00108 {
00109         return nextBehavior;
00110 }
00111 
00112 BehaviorType Behavior::getType() const
00113 {
00114         return type;
00115 }
00116 
00117 bool Behavior::canTransitionTo(const Behavior& toBehavior) const
00118 {
00119         return BehaviorHelper::isAllowedBehaviorTransition(*this, toBehavior);
00120 }
00121 
00122 // static Helpers
00123 Behavior* Behavior::behaviorFromID(uint64_t behaviorID)
00124 {
00125         return (Behavior*)behaviorID;
00126 }
00127 
00128 uint64_t Behavior::behaviorToID(Behavior* behavior)
00129 {
00130         return (uint64_t)behavior;
00131 }
00132 bool Behavior::exists(Behavior *behavior)
00133 {
00134         return BehaviorContainer::behaviorInstanceExists(behavior);
00135 }
00136 bool Behavior::exists(uint64_t behaviorID)
00137 {
00138         return  BehaviorContainer::behaviorInstanceExists(behaviorFromID(behaviorID));
00139 }
00140 
00141 
00142 }
00143 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


tk_behavior
Author(s): Dr. Antonio Franchi and Martin Riedel
autogenerated on Mon Nov 11 2013 11:13:36