00001 /* 00002 * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland 00003 * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland 00004 * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland 00005 * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland 00006 * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland 00007 * 00008 * Licensed under the Apache License, Version 2.0 (the "License"); 00009 * you may not use this file except in compliance with the License. 00010 * You may obtain a copy of the License at 00011 * 00012 * http://www.apache.org/licenses/LICENSE-2.0 00013 00014 * Unless required by applicable law or agreed to in writing, software 00015 * distributed under the License is distributed on an "AS IS" BASIS, 00016 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00017 * See the License for the specific language governing permissions and 00018 * limitations under the License. 00019 */ 00020 00021 00022 #ifndef ROTORS_JOY_INTERFACE_JOY_H_ 00023 #define ROTORS_JOY_INTERFACE_JOY_H_ 00024 00025 #include <geometry_msgs/PoseStamped.h> 00026 #include <mav_msgs/RollPitchYawrateThrust.h> 00027 #include <ros/ros.h> 00028 #include <sensor_msgs/Joy.h> 00029 00030 struct Axes { 00031 int roll; 00032 int pitch; 00033 int thrust; 00034 int roll_direction; 00035 int pitch_direction; 00036 int thrust_direction; 00037 }; 00038 00039 struct Buttons { 00040 int takeoff; 00041 int land; 00042 int ctrl_enable; 00043 int ctrl_mode; 00044 int yaw_left; 00045 int yaw_right; 00046 }; 00047 00048 struct Max { 00049 double v_xy; 00050 double roll; 00051 double pitch; 00052 double rate_yaw; 00053 double thrust; 00054 }; 00055 00056 class Joy { 00057 typedef sensor_msgs::Joy::_buttons_type ButtonType; 00058 00059 private: 00060 ros::NodeHandle nh_; 00061 ros::Publisher ctrl_pub_; 00062 ros::Subscriber joy_sub_; 00063 00064 std::string namespace_; 00065 00066 Axes axes_; 00067 Buttons buttons_; 00068 00069 mav_msgs::RollPitchYawrateThrust control_msg_; 00070 geometry_msgs::PoseStamped pose_; 00071 sensor_msgs::Joy current_joy_; 00072 00073 Max max_; 00074 00075 double current_yaw_vel_; 00076 double v_yaw_step_; 00077 00078 bool is_fixed_wing_; 00079 00080 void StopMav(); 00081 00082 void JoyCallback(const sensor_msgs::JoyConstPtr& msg); 00083 void Publish(); 00084 00085 public: 00086 Joy(); 00087 }; 00088 00089 #endif // ROTORS_JOY_INTERFACE_JOY_H_