#include <TeleKybCore.hpp>
Public Member Functions | |
| BehaviorController * | getBehaviorController () const | 
| OptionController * | getOptionController () const | 
| virtual | ~TeleKybCore () | 
Static Public Member Functions | |
| static TeleKybCore * | getTeleKybCore (int robotID_) | 
| static bool | getTeleKybCoreMainNodeHandle (int robotID_, ros::NodeHandle &nodeHandle_, double waitTime_=0.0) | 
Protected Member Functions | |
| void | createBehaviorController () | 
| void | createOptionController () | 
| bool | isOk () const | 
Protected Attributes | |
| BehaviorController * | behaviorController | 
| ros::NodeHandle | mainNodeHandle | 
| OptionController * | optionController | 
| int | robotID | 
Private Member Functions | |
| TeleKybCore (int robotID_, const std::string &mainHandleNamespace) | |
Definition at line 20 of file TeleKybCore.hpp.
| TELEKYB_INTERFACE_NAMESPACE::TeleKybCore::TeleKybCore | ( | int | robotID_, | 
| const std::string & | mainHandleNamespace | ||
| ) |  [private] | 
        
Definition at line 22 of file TeleKybCore.cpp.
| TELEKYB_INTERFACE_NAMESPACE::TeleKybCore::~TeleKybCore | ( | ) |  [virtual] | 
        
Definition at line 33 of file TeleKybCore.cpp.
| void TELEKYB_INTERFACE_NAMESPACE::TeleKybCore::createBehaviorController | ( | ) |  [protected] | 
        
Definition at line 63 of file TeleKybCore.cpp.
| void TELEKYB_INTERFACE_NAMESPACE::TeleKybCore::createOptionController | ( | ) |  [protected] | 
        
Definition at line 50 of file TeleKybCore.cpp.
Definition at line 44 of file TeleKybCore.cpp.
Definition at line 39 of file TeleKybCore.cpp.
| TeleKybCore * TELEKYB_INTERFACE_NAMESPACE::TeleKybCore::getTeleKybCore | ( | int | robotID_ | ) |  [static] | 
        
Definition at line 89 of file TeleKybCore.cpp.
| bool TELEKYB_INTERFACE_NAMESPACE::TeleKybCore::getTeleKybCoreMainNodeHandle | ( | int | robotID_, | 
| ros::NodeHandle & | nodeHandle_, | ||
| double | waitTime_ = 0.0  | 
        ||
| ) |  [static] | 
        
Definition at line 120 of file TeleKybCore.cpp.
| bool TELEKYB_INTERFACE_NAMESPACE::TeleKybCore::isOk | ( | ) |  const [protected] | 
        
Definition at line 74 of file TeleKybCore.cpp.
Definition at line 33 of file TeleKybCore.hpp.
Definition at line 27 of file TeleKybCore.hpp.
Definition at line 30 of file TeleKybCore.hpp.
int TELEKYB_INTERFACE_NAMESPACE::TeleKybCore::robotID [protected] | 
        
Definition at line 26 of file TeleKybCore.hpp.