$search
00001 //================================================================================================= 00002 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt 00003 // All rights reserved. 00004 00005 // Redistribution and use in source and binary forms, with or without 00006 // modification, are permitted provided that the following conditions are met: 00007 // * Redistributions of source code must retain the above copyright 00008 // notice, this list of conditions and the following disclaimer. 00009 // * Redistributions in binary form must reproduce the above copyright 00010 // notice, this list of conditions and the following disclaimer in the 00011 // documentation and/or other materials provided with the distribution. 00012 // * Neither the name of the Flight Systems and Automatic Control group, 00013 // TU Darmstadt, nor the names of its contributors may be used to 00014 // endorse or promote products derived from this software without 00015 // specific prior written permission. 00016 00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00027 //================================================================================================= 00028 00029 00030 #include <ros/ros.h> 00031 #include <sensor_msgs/Joy.h> 00032 #include <geometry_msgs/Twist.h> 00033 00034 namespace hector_quadrotor { 00035 00036 class Teleop 00037 { 00038 private: 00039 ros::NodeHandle node_handle_; 00040 ros::Subscriber joy_subscriber_; 00041 ros::Publisher velocity_publisher_; 00042 geometry_msgs::Twist velocity_; 00043 00044 struct Axis 00045 { 00046 int axis; 00047 double max; 00048 }; 00049 00050 struct Button 00051 { 00052 unsigned int button; 00053 }; 00054 00055 struct { 00056 Axis x; 00057 Axis y; 00058 Axis z; 00059 Axis yaw; 00060 } axes_; 00061 00062 struct 00063 { 00064 } buttons_; 00065 00066 public: 00067 Teleop() 00068 { 00069 ros::NodeHandle params("~"); 00070 axes_.x.axis = 0; 00071 axes_.x.max = 2.0; 00072 axes_.y.axis = 0; 00073 axes_.y.max = 2.0; 00074 axes_.z.axis = 0; 00075 axes_.z.max = 2.0; 00076 axes_.yaw.axis = 0; 00077 axes_.yaw.max = 90.0*M_PI/180.0; 00078 params.getParam("x_axis", axes_.x.axis); 00079 params.getParam("y_axis", axes_.y.axis); 00080 params.getParam("z_axis", axes_.z.axis); 00081 params.getParam("yaw_axis", axes_.yaw.axis); 00082 params.getParam("x_velocity_max", axes_.x.max); 00083 params.getParam("y_velocity_max", axes_.y.max); 00084 params.getParam("z_velocity_max", axes_.z.max); 00085 params.getParam("yaw_velocity_max", axes_.yaw.max); 00086 00087 joy_subscriber_ = node_handle_.subscribe<sensor_msgs::Joy>("joy", 1, boost::bind(&Teleop::joyCallback, this, _1)); 00088 velocity_publisher_ = node_handle_.advertise<geometry_msgs::Twist>("cmd_vel", 10); 00089 } 00090 00091 ~Teleop() 00092 { 00093 stop(); 00094 } 00095 00096 void joyCallback(const sensor_msgs::JoyConstPtr& joy) 00097 { 00098 velocity_.linear.x = getAxis(joy, axes_.x.axis) * axes_.x.max; 00099 velocity_.linear.y = getAxis(joy, axes_.y.axis) * axes_.y.max; 00100 velocity_.linear.z = getAxis(joy, axes_.z.axis) * axes_.z.max; 00101 velocity_.angular.z = getAxis(joy, axes_.yaw.axis) * axes_.yaw.max; 00102 velocity_publisher_.publish(velocity_); 00103 } 00104 00105 sensor_msgs::Joy::_axes_type::value_type getAxis(const sensor_msgs::JoyConstPtr& joy, int axis) 00106 { 00107 if (axis == 0) return 0; 00108 sensor_msgs::Joy::_axes_type::value_type sign = 1.0; 00109 if (axis < 0) { sign = -1.0; axis = -axis; } 00110 if ((size_t)axis > joy->axes.size()) return 0; 00111 return sign * joy->axes[axis - 1]; 00112 } 00113 00114 sensor_msgs::Joy::_buttons_type::value_type getButton(const sensor_msgs::JoyConstPtr& joy, int button) 00115 { 00116 if (button <= 0) return 0; 00117 if ((size_t)button > joy->axes.size()) return 0; 00118 return joy->buttons[button - 1]; 00119 } 00120 00121 void stop() 00122 { 00123 velocity_ = geometry_msgs::Twist(); 00124 velocity_publisher_.publish(velocity_); 00125 } 00126 }; 00127 00128 } // namespace hector_quadrotor 00129 00130 int main(int argc, char **argv) 00131 { 00132 ros::init(argc, argv, "quadrotor_teleop"); 00133 00134 hector_quadrotor::Teleop teleop; 00135 ros::spin(); 00136 00137 return 0; 00138 }