#include <Formation.hpp>
Definition at line 35 of file Formation.hpp.
Definition at line 25 of file Formation.cpp.
void telekyb_behavior::Formation::destroy | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 121 of file Formation.cpp.
void telekyb_behavior::Formation::didBecomeActive | ( | const TKState & | currentState, |
const Behavior & | previousBehavior | ||
) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 240 of file Formation.cpp.
void telekyb_behavior::Formation::didBecomeInActive | ( | const TKState & | currentState, |
const Behavior & | nextBehavior | ||
) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 261 of file Formation.cpp.
Velocity3D telekyb_behavior::Formation::getFormationVirtPointVel | ( | ) | [protected] |
Definition at line 327 of file Formation.cpp.
void telekyb_behavior::Formation::initialize | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 70 of file Formation.cpp.
bool telekyb_behavior::Formation::isValid | ( | const TKState & | currentState | ) | const [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 322 of file Formation.cpp.
void telekyb_behavior::Formation::joystickCB | ( | const sensor_msgs::Joy::ConstPtr & | msg | ) | [protected] |
Definition at line 32 of file Formation.cpp.
void telekyb_behavior::Formation::obsPointCB | ( | const telekyb_msgs::StampedPointArray::ConstPtr & | obsPointsMsg | ) | [protected] |
Definition at line 57 of file Formation.cpp.
void telekyb_behavior::Formation::trajectoryStepActive | ( | const TKState & | currentState, |
TKTrajectory & | generatedTrajInput | ||
) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 272 of file Formation.cpp.
void telekyb_behavior::Formation::trajectoryStepCreation | ( | const TKState & | currentState, |
TKTrajectory & | generatedTrajInput | ||
) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 266 of file Formation.cpp.
void telekyb_behavior::Formation::trajectoryStepTermination | ( | const TKState & | currentState, |
TKTrajectory & | generatedTrajInput | ||
) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 316 of file Formation.cpp.
void telekyb_behavior::Formation::userVelocityCB | ( | const geometry_msgs::Vector3Stamped::ConstPtr & | msg | ) | [protected] |
Definition at line 46 of file Formation.cpp.
bool telekyb_behavior::Formation::willBecomeActive | ( | const TKState & | currentState, |
const Behavior & | previousBehavior | ||
) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 126 of file Formation.cpp.
void telekyb_behavior::Formation::willBecomeInActive | ( | const TKState & | currentState, |
const Behavior & | nextBehavior | ||
) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 245 of file Formation.cpp.
bool telekyb_behavior::Formation::deadManPressed [protected] |
Definition at line 76 of file Formation.hpp.
std::vector<double> telekyb_behavior::Formation::distanceVector [protected] |
Definition at line 54 of file Formation.hpp.
std::vector< CoTanAttractiveGradient*> telekyb_behavior::Formation::formationAttractiveGradientVector [protected] |
Definition at line 98 of file Formation.hpp.
std::vector< CoTanRepulsiveGradient*> telekyb_behavior::Formation::formationRepulsiveGradientVector [protected] |
Definition at line 97 of file Formation.hpp.
ros::Subscriber telekyb_behavior::Formation::joySub [protected] |
Definition at line 61 of file Formation.hpp.
std::vector<Position3D> telekyb_behavior::Formation::lastObstaclePoints [protected] |
Definition at line 48 of file Formation.hpp.
Definition at line 67 of file Formation.hpp.
Definition at line 62 of file Formation.hpp.
Definition at line 85 of file Formation.hpp.
Definition at line 73 of file Formation.hpp.
Option<double>* telekyb_behavior::Formation::tFormationAttrGain [protected] |
Definition at line 89 of file Formation.hpp.
Option<bool>* telekyb_behavior::Formation::tFormationDoYawControl [protected] |
Definition at line 91 of file Formation.hpp.
double telekyb_behavior::Formation::tFormationInitialYawAngle [protected] |
Definition at line 93 of file Formation.hpp.
Option<double>* telekyb_behavior::Formation::tFormationRepulGain [protected] |
Definition at line 90 of file Formation.hpp.
Option<double>* telekyb_behavior::Formation::tFormationRepulMinDist [protected] |
Definition at line 88 of file Formation.hpp.
Option< std::string >* telekyb_behavior::Formation::tJoystickTopic [protected] |
Definition at line 40 of file Formation.hpp.
Option<double>* telekyb_behavior::Formation::tMaxYawRate [protected] |
Definition at line 51 of file Formation.hpp.
Option< std::vector<int> >* telekyb_behavior::Formation::tNeighbors [protected] |
Definition at line 37 of file Formation.hpp.
Option< std::string >* telekyb_behavior::Formation::tObsPointsTopicName [protected] |
Definition at line 47 of file Formation.hpp.
Option< bool >* telekyb_behavior::Formation::tVelocityInputEnabled [protected] |
Definition at line 41 of file Formation.hpp.
Option< std::string >* telekyb_behavior::Formation::tVelocityInputTopic [protected] |
Definition at line 42 of file Formation.hpp.
Definition at line 60 of file Formation.hpp.
bool telekyb_behavior::Formation::valid [protected] |
Definition at line 79 of file Formation.hpp.
Position3D telekyb_behavior::Formation::virtualPoint [protected] |
Definition at line 57 of file Formation.hpp.