Joystick.hpp
Go to the documentation of this file.
00001 /*
00002  * Joystick.hpp
00003  *
00004  *  Created on: Nov 12, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef JOYSTICK_HPP_
00009 #define JOYSTICK_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 #include <tk_behavior/Behavior.hpp>
00013 
00014 #include <telekyb_base/Spaces/Angle.hpp>
00015 
00016 // plugin stuff
00017 #include <pluginlib/class_list_macros.h>
00018 
00019 // sensormsgs
00020 #include <sensor_msgs/Joy.h>
00021 
00022 using namespace TELEKYB_NAMESPACE;
00023 
00024 namespace telekyb_behavior {
00025 
00026 class Joystick : public Behavior {
00027 protected:
00028         Option<std::string>* tJoystickTopic;
00029         Option<bool>* tJoystickUsePositionMode;
00030         Option<double>* tJoystickYawRateScale;
00031 
00032         //input is interpreted in local frame!
00033         Option<bool>* tJoystickUseRelativeMode;
00034         //disable dead man switch?
00035         Option<bool>* tJoystickUseDeadManSwitch;
00036 
00037         // ROS
00038         ros::NodeHandle nodeHandle;
00039         ros::Subscriber joySub;
00040 
00041         void joystickCB(const sensor_msgs::Joy::ConstPtr& msg);
00042 
00043         Velocity3D lastVelocityInput;
00044         double lastYawRateInput;
00045 
00046         // Integrated Position for Velocity Mode
00047         Position3D posModeCurPosition;
00048         Angle posModeCurYawAngle;
00049         Time posModeLastInputTime;
00050 
00051         // Outputfield
00052         bool valid;
00053 
00054 public:
00055         Joystick();
00056 
00057         virtual void initialize();
00058         virtual void destroy();
00059 
00060         // Called directly after Change Event is registered.
00061         virtual bool willBecomeActive(const TKState& currentState, const Behavior& previousBehavior);
00062         // Called after actual Switch. Note: During execution trajectoryStepCreation is used
00063         virtual void didBecomeActive(const TKState& currentState, const Behavior& previousBehavior);
00064         // Called directly after Change Event is registered: During execution trajectoryStepTermination is used
00065         virtual void willBecomeInActive(const TKState& currentState, const Behavior& nextBehavior);
00066         // Called after actual Switch. Runs in seperate Thread.
00067         virtual void didBecomeInActive(const TKState& currentState, const Behavior& nextBehavior);
00068 
00069         // called everytime a new TKState is available AND it is the NEW Behavior of an active Switch
00070         virtual void trajectoryStepCreation(const TKState& currentState, TKTrajectory& generatedTrajInput);
00071 
00072         // called everytime a new TKState is available. Should return false if invalid (swtich to next behavior, or Hover if undef).
00073         virtual void trajectoryStepActive(const TKState& currentState, TKTrajectory& generatedTrajInput);
00074 
00075         // called everytime a new TKState is available AND it is the OLD Behavior of an active Switch
00076         virtual void trajectoryStepTermination(const TKState& currentState, TKTrajectory& generatedTrajInput);
00077 
00078         // Return true if the active Behavior is (still) valid. Initiate Switch otherwise
00079         virtual bool isValid(const TKState& currentState) const;
00080 };
00081 
00082 }
00083 
00084 #endif /* JOYSTICK_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


tk_be_common
Author(s): Martin Riedel
autogenerated on Mon Nov 11 2013 11:14:29