Calibrator.hpp
Go to the documentation of this file.
00001 /*
00002  * Calibrator.hpp
00003  *
00004  *  Created on: Nov 15, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef CALIBRATOR_HPP_
00009 #define CALIBRATOR_HPP_
00010 
00011 #include <telekyb_base/Options.hpp>
00012 
00013 #include <sensor_msgs/Joy.h>
00014 
00015 #include <telekyb_interface/TeleKybCore.hpp>
00016 #include <telekyb_interface/MKInterface.hpp>
00017 
00018 
00019 using namespace telekyb;
00020 
00021 class CalibratorOptions : public OptionContainer
00022 {
00023 public:
00024         Option<int>* robotID;
00025         Option<std::string>* tJoystickTopic;
00026         Option<bool>* tUseMKInterface;
00027         CalibratorOptions();
00028 };
00029 
00030 class Calibrator : telekyb_interface::ActiveBehaviorListener {
00031 protected:
00032         CalibratorOptions options;
00033         // ROS
00034         ros::NodeHandle mainNodeHandle;
00035         ros::Subscriber joySub;
00036 
00037         // the System
00038         telekyb_interface::TeleKybCore* core;
00039         // BehaviorController
00040         telekyb_interface::BehaviorController* bController;
00041         telekyb_interface::OptionController *oController;
00042 
00043         // Optional MKInterface
00044         telekyb_interface::MKInterface* mkInterface;
00045 
00046 
00047         // System Behaviors
00048         telekyb_interface::Behavior ground;
00049         telekyb_interface::Behavior hover;
00050         telekyb_interface::Behavior normalBreak;
00051         telekyb_interface::Behavior takeOff;
00052         telekyb_interface::Behavior land;
00053 
00054         // Calibrator
00055         telekyb_interface::Behavior calibrator;
00056 
00057         // Behavior
00058         telekyb_interface::Behavior* activeBehaviorPtr;
00059 
00060         //double saveIntegralGain;
00061 
00062 
00063 
00064 
00065 public:
00066         Calibrator();
00067         virtual ~Calibrator();
00068 
00069         // setup Behaviors
00070         void setupCalibrator();
00071 
00072         void activeBehaviorChanged(telekyb_interface::Behavior newActiveBehavior);
00073 
00074         void joystickCB(const sensor_msgs::Joy::ConstPtr& msg);
00075 };
00076 
00077 #endif /* CALIBRATOR_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


tk_mk_tools
Author(s): Martin Riedel
autogenerated on Thu Apr 25 2013 11:16:03