Quadrotor_tk_Handler.h
Go to the documentation of this file.
00001 // Copyright 2006-2013 Dr. Marc Andreas Freese. All rights reserved. 
00002 // marc@coppeliarobotics.com
00003 // www.coppeliarobotics.com
00004 // 
00005 // -------------------------------------------------------------------
00006 // This file is distributed in the hope that it will be useful,
00007 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00008 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
00009 // 
00010 // You are free to use/modify/distribute this file for whatever purpose!
00011 // -------------------------------------------------------------------
00012 //
00013 // This file was automatically created for V-REP release V3.0.5 on October 26th 2013
00014 
00015 #ifndef QUADROTOR_TK_HANDLER_H
00016 #define QUADROTOR_TK_HANDLER_H
00017 
00018 #include "vrep_ros_plugin/GenericObjectHandler.h"
00019 
00020 #include "vrep_ros_plugin/access.h"
00021 #include <ros/time.h>
00022 #include <telekyb_msgs/TKMotorCommands.h>
00023 #include <telekyb_msgs/TKCommands.h>
00024 
00030 class Quadrotor_tk_Handler : public GenericObjectHandler
00031 {
00032 public:
00033         Quadrotor_tk_Handler();
00034         ~Quadrotor_tk_Handler();
00035 
00036         void synchronize();
00037         void handleSimulation();
00038         unsigned int getObjectType() const;
00039 
00040 protected:
00041 
00042         void _initialize();
00047         ros::Time _previousTime;
00051         float _integralTermRoll;
00052         float _integralTermPitch;
00053 
00057         float _torqueToForceRatio;
00058 
00062         int _handleOfJoint[4];
00063 
00067         int _handleOfCoM;
00068 
00072         simFloat _quadrotorMass;
00073 
00077         simFloat _jointPosition[4][3];
00078 
00082         ros::Publisher _pub;
00083 
00087         ros::Publisher _pubIMU;
00088 
00092         ros::Subscriber _sub;
00093 
00097         ros::Time _lastReceivedCmdTime;
00098 
00102         ros::Time _lastPrintedMsg;
00103 
00107         std::vector<double> _tkMotorCommands;
00108 
00112         telekyb_msgs::TKCommands _tkCommands;
00113 
00117         simFloat _att_cutoff;
00118 
00122         simFloat _att_damping;
00123 
00127         simFloat _kp_yaw;
00128 
00132         CustomDataHeaders::QuadrotorCtrlMode _ctrlMode;
00133 
00138         void tkMotorCommandsCallback(const telekyb_msgs::TKMotorCommands::ConstPtr& msg);
00139 
00144         void tkCommandsCallback(const telekyb_msgs::TKCommands::ConstPtr& msg);
00145 };
00146 
00147 
00148 #endif // ndef QUADROTOR_TK_HANDLER_H


quadrotor_tk_handler
Author(s):
autogenerated on Sat May 9 2015 13:16:55