#include <AbstractGraphNode.hpp>
Public Member Functions | |
AbstractGraphNode (const std::string &name_, const BehaviorType &type_) | |
void | addNeighbor (int robotID) |
bool | allNeighborsValid () const |
void | removeNeighbor (int robotID) |
virtual | ~AbstractGraphNode () |
Protected Member Functions | |
void | publishConditionDone (bool conditionDone_=true) const |
void | publishInitDone (bool initDone_=true) const |
void | publishVP (const Eigen::Vector3d &virtualPoint) const |
Protected Attributes | |
ros::Publisher | formationConditionDonePublisher |
ros::Publisher | initDonePublisher |
std::map< int, Neighbor * > | neighbors |
ros::NodeHandle | nodeHandle |
int | nodeID |
ros::Publisher | vpPublisher |
Definition at line 23 of file AbstractGraphNode.hpp.
telekyb_behavior::AbstractGraphNode::AbstractGraphNode | ( | const std::string & | name_, |
const BehaviorType & | type_ | ||
) |
Definition at line 17 of file AbstractGraphNode.cpp.
telekyb_behavior::AbstractGraphNode::~AbstractGraphNode | ( | ) | [virtual] |
Definition at line 36 of file AbstractGraphNode.cpp.
void telekyb_behavior::AbstractGraphNode::addNeighbor | ( | int | robotID | ) |
Definition at line 66 of file AbstractGraphNode.cpp.
bool telekyb_behavior::AbstractGraphNode::allNeighborsValid | ( | ) | const |
Definition at line 84 of file AbstractGraphNode.cpp.
void telekyb_behavior::AbstractGraphNode::publishConditionDone | ( | bool | conditionDone_ = true | ) | const [protected] |
Definition at line 58 of file AbstractGraphNode.cpp.
void telekyb_behavior::AbstractGraphNode::publishInitDone | ( | bool | initDone_ = true | ) | const [protected] |
Definition at line 51 of file AbstractGraphNode.cpp.
void telekyb_behavior::AbstractGraphNode::publishVP | ( | const Eigen::Vector3d & | virtualPoint | ) | const [protected] |
Definition at line 41 of file AbstractGraphNode.cpp.
void telekyb_behavior::AbstractGraphNode::removeNeighbor | ( | int | robotID | ) |
Definition at line 76 of file AbstractGraphNode.cpp.
Definition at line 32 of file AbstractGraphNode.hpp.
Definition at line 31 of file AbstractGraphNode.hpp.
std::map<int, Neighbor*> telekyb_behavior::AbstractGraphNode::neighbors [protected] |
Definition at line 26 of file AbstractGraphNode.hpp.
Reimplemented from TELEKYB_NAMESPACE::Behavior.
Definition at line 28 of file AbstractGraphNode.hpp.
int telekyb_behavior::AbstractGraphNode::nodeID [protected] |
Definition at line 25 of file AbstractGraphNode.hpp.
Definition at line 30 of file AbstractGraphNode.hpp.