#include <Calibrator.hpp>
Public Member Functions | |
| void | activeBehaviorChanged (telekyb_interface::Behavior newActiveBehavior) |
| Calibrator () | |
| void | joystickCB (const sensor_msgs::Joy::ConstPtr &msg) |
| void | setupCalibrator () |
| virtual | ~Calibrator () |
Protected Attributes | |
| telekyb_interface::Behavior * | activeBehaviorPtr |
| telekyb_interface::BehaviorController * | bController |
| telekyb_interface::Behavior | calibrator |
| telekyb_interface::TeleKybCore * | core |
| telekyb_interface::Behavior | ground |
| telekyb_interface::Behavior | hover |
| ros::Subscriber | joySub |
| telekyb_interface::Behavior | land |
| ros::NodeHandle | mainNodeHandle |
| telekyb_interface::MKInterface * | mkInterface |
| telekyb_interface::Behavior | normalBreak |
| telekyb_interface::OptionController * | oController |
| CalibratorOptions | options |
| telekyb_interface::Behavior | takeOff |
Definition at line 30 of file Calibrator/Calibrator.hpp.
Definition at line 25 of file Calibrator/Calibrator.cpp.
| Calibrator::~Calibrator | ( | ) | [virtual] |
Definition at line 58 of file Calibrator/Calibrator.cpp.
| void Calibrator::activeBehaviorChanged | ( | telekyb_interface::Behavior | newActiveBehavior | ) |
Definition at line 189 of file Calibrator/Calibrator.cpp.
| void Calibrator::joystickCB | ( | const sensor_msgs::Joy::ConstPtr & | msg | ) |
Definition at line 119 of file Calibrator/Calibrator.cpp.
| void Calibrator::setupCalibrator | ( | ) |
Definition at line 65 of file Calibrator/Calibrator.cpp.
telekyb_interface::Behavior* Calibrator::activeBehaviorPtr [protected] |
Definition at line 58 of file Calibrator/Calibrator.hpp.
telekyb_interface::BehaviorController* Calibrator::bController [protected] |
Definition at line 40 of file Calibrator/Calibrator.hpp.
telekyb_interface::Behavior Calibrator::calibrator [protected] |
Definition at line 55 of file Calibrator/Calibrator.hpp.
telekyb_interface::TeleKybCore* Calibrator::core [protected] |
Definition at line 38 of file Calibrator/Calibrator.hpp.
telekyb_interface::Behavior Calibrator::ground [protected] |
Definition at line 48 of file Calibrator/Calibrator.hpp.
telekyb_interface::Behavior Calibrator::hover [protected] |
Definition at line 49 of file Calibrator/Calibrator.hpp.
ros::Subscriber Calibrator::joySub [protected] |
Definition at line 35 of file Calibrator/Calibrator.hpp.
telekyb_interface::Behavior Calibrator::land [protected] |
Definition at line 52 of file Calibrator/Calibrator.hpp.
ros::NodeHandle Calibrator::mainNodeHandle [protected] |
Definition at line 34 of file Calibrator/Calibrator.hpp.
telekyb_interface::MKInterface* Calibrator::mkInterface [protected] |
Definition at line 44 of file Calibrator/Calibrator.hpp.
telekyb_interface::Behavior Calibrator::normalBreak [protected] |
Definition at line 50 of file Calibrator/Calibrator.hpp.
telekyb_interface::OptionController* Calibrator::oController [protected] |
Definition at line 41 of file Calibrator/Calibrator.hpp.
CalibratorOptions Calibrator::options [protected] |
Definition at line 32 of file Calibrator/Calibrator.hpp.
telekyb_interface::Behavior Calibrator::takeOff [protected] |
Definition at line 51 of file Calibrator/Calibrator.hpp.