#include <Neighbor.hpp>
Public Member Functions | |
bool | formationConditionDone () const |
Time | getElapsedMessageTime () const |
Position3D | getVirtualPoint () const |
bool | initDone () const |
Neighbor (int robotID_) | |
bool | receivedOnce () const |
virtual | ~Neighbor () |
Protected Member Functions | |
void | neighborFormationConditionDone (const std_msgs::Bool::ConstPtr &msg) |
void | neighborInitDone (const std_msgs::Bool::ConstPtr &msg) |
void | neighborVPCallback (const geometry_msgs::PointStamped::ConstPtr &stateMsg) |
Protected Attributes | |
ros::Subscriber | formationConditionDoneSub |
bool | formationConditionDoneVar |
ros::Subscriber | initDoneSub |
bool | initDoneVar |
Timer | messageTimer |
ros::NodeHandle | nodeHandle |
bool | receivedOnceVar |
int | robotID |
Position3D | virtualPoint |
ros::Subscriber | vpSub |
Definition at line 32 of file Neighbor.hpp.
telekyb_behavior::Neighbor::Neighbor | ( | int | robotID_ | ) |
Definition at line 16 of file Neighbor.cpp.
telekyb_behavior::Neighbor::~Neighbor | ( | ) | [virtual] |
Definition at line 35 of file Neighbor.cpp.
bool telekyb_behavior::Neighbor::formationConditionDone | ( | ) | const |
Definition at line 72 of file Neighbor.cpp.
Definition at line 82 of file Neighbor.cpp.
Definition at line 62 of file Neighbor.cpp.
bool telekyb_behavior::Neighbor::initDone | ( | ) | const |
Definition at line 77 of file Neighbor.cpp.
void telekyb_behavior::Neighbor::neighborFormationConditionDone | ( | const std_msgs::Bool::ConstPtr & | msg | ) | [protected] |
Definition at line 56 of file Neighbor.cpp.
void telekyb_behavior::Neighbor::neighborInitDone | ( | const std_msgs::Bool::ConstPtr & | msg | ) | [protected] |
Definition at line 51 of file Neighbor.cpp.
void telekyb_behavior::Neighbor::neighborVPCallback | ( | const geometry_msgs::PointStamped::ConstPtr & | stateMsg | ) | [protected] |
Definition at line 40 of file Neighbor.cpp.
bool telekyb_behavior::Neighbor::receivedOnce | ( | ) | const |
Definition at line 67 of file Neighbor.cpp.
Definition at line 46 of file Neighbor.hpp.
bool telekyb_behavior::Neighbor::formationConditionDoneVar [protected] |
Definition at line 39 of file Neighbor.hpp.
Definition at line 45 of file Neighbor.hpp.
bool telekyb_behavior::Neighbor::initDoneVar [protected] |
Definition at line 37 of file Neighbor.hpp.
Timer telekyb_behavior::Neighbor::messageTimer [protected] |
Definition at line 49 of file Neighbor.hpp.
Definition at line 43 of file Neighbor.hpp.
bool telekyb_behavior::Neighbor::receivedOnceVar [protected] |
Definition at line 36 of file Neighbor.hpp.
int telekyb_behavior::Neighbor::robotID [protected] |
Definition at line 34 of file Neighbor.hpp.
Position3D telekyb_behavior::Neighbor::virtualPoint [protected] |
Definition at line 35 of file Neighbor.hpp.
ros::Subscriber telekyb_behavior::Neighbor::vpSub [protected] |
Definition at line 44 of file Neighbor.hpp.