00001 /* 00002 * Neighbor.hpp 00003 * 00004 * Created on: Feb 12, 2012 00005 * Author: mriedel 00006 */ 00007 00008 00009 // This is a quick & dirty implementation for IAS Deadline. HAS TO BE REWRITTEN!!! 00010 00011 #ifndef NEIGHBOR_HPP_ 00012 #define NEIGHBOR_HPP_ 00013 00014 #include <telekyb_defines/telekyb_defines.hpp> 00015 #include <telekyb_base/Messages.hpp> 00016 00017 #include <telekyb_base/Time.hpp> 00018 00019 #include <ros/ros.h> 00020 00021 #include <geometry_msgs/PointStamped.h> 00022 #include <std_msgs/Bool.h> 00023 00024 #define VP_TOPIC "VirtualPoint" 00025 #define INITDONE_TOPIC "VP_InitDone" 00026 #define CONDITIONDONE_TOPIC "VP_ConditionDone" 00027 00028 using namespace TELEKYB_NAMESPACE; 00029 00030 namespace telekyb_behavior { 00031 00032 class Neighbor { 00033 protected: 00034 int robotID; 00035 Position3D virtualPoint; 00036 bool receivedOnceVar; 00037 bool initDoneVar; 00038 00039 bool formationConditionDoneVar; 00040 00041 00042 // Nodehandle for communication 00043 ros::NodeHandle nodeHandle; 00044 ros::Subscriber vpSub; 00045 ros::Subscriber initDoneSub; 00046 ros::Subscriber formationConditionDoneSub; 00047 00048 // Messagetimer 00049 Timer messageTimer; 00050 00051 00052 void neighborVPCallback(const geometry_msgs::PointStamped::ConstPtr& stateMsg); 00053 void neighborInitDone(const std_msgs::Bool::ConstPtr& msg); 00054 void neighborFormationConditionDone(const std_msgs::Bool::ConstPtr& msg); 00055 00056 public: 00057 Neighbor(int robotID_); 00058 virtual ~Neighbor(); 00059 00060 Position3D getVirtualPoint() const; 00061 bool receivedOnce() const; 00062 bool initDone() const; 00063 bool formationConditionDone() const; 00064 00065 Time getElapsedMessageTime() const; 00066 00067 00068 }; 00069 00070 } 00071 00072 #endif /* NEIGHBOR_HPP_ */