quadrotor_teleop.cpp
Go to the documentation of this file.
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 class Teleop
00035 {
00036 private:
00037   ros::NodeHandle node_handle_;
00038   ros::Subscriber joy_subscriber_;
00039 
00040   ros::Publisher velocity_publisher_;
00041   geometry_msgs::Twist velocity_;
00042 
00043   struct Axis
00044   {
00045     int axis;
00046     double max;
00047   };
00048 
00049   struct Button
00050   {
00051     int button;
00052   };
00053 
00054   struct
00055   {
00056     Axis x;
00057     Axis y;
00058     Axis z;
00059     Axis yaw;
00060   } axes_;
00061 
00062 public:
00063   Teleop()
00064   {
00065     ros::NodeHandle params("~");
00066 
00067     params.param<int>("x_axis", axes_.x.axis, 4);
00068     params.param<int>("y_axis", axes_.y.axis, 3);
00069     params.param<int>("z_axis", axes_.z.axis, 2);
00070     params.param<int>("yaw_axis", axes_.yaw.axis, 1);
00071 
00072     params.param<double>("yaw_velocity_max", axes_.yaw.max, 90.0 * M_PI / 180.0);
00073 
00074     params.param<double>("x_velocity_max", axes_.x.max, 2.0);
00075     params.param<double>("y_velocity_max", axes_.y.max, 2.0);
00076     params.param<double>("z_velocity_max", axes_.z.max, 2.0);
00077 
00078     joy_subscriber_ = node_handle_.subscribe<sensor_msgs::Joy>("joy", 1, boost::bind(&Teleop::joyTwistCallback, this, _1));
00079     velocity_publisher_ = node_handle_.advertise<geometry_msgs::Twist>("cmd_vel", 10);
00080   }
00081 
00082   ~Teleop()
00083   {
00084     stop();
00085   }
00086 
00087   void joyTwistCallback(const sensor_msgs::JoyConstPtr &joy)
00088   {
00089     velocity_.linear.x = getAxis(joy, axes_.x);
00090     velocity_.linear.y = getAxis(joy, axes_.y);
00091     velocity_.linear.z = getAxis(joy, axes_.z);
00092     velocity_.angular.z = getAxis(joy, axes_.yaw);
00093     velocity_publisher_.publish(velocity_);
00094   }
00095 
00096   sensor_msgs::Joy::_axes_type::value_type getAxis(const sensor_msgs::JoyConstPtr &joy, Axis axis)
00097   {
00098     if (axis.axis == 0)
00099     {return 0;}
00100     sensor_msgs::Joy::_axes_type::value_type sign = 1.0;
00101     if (axis.axis < 0)
00102     {
00103       sign = -1.0;
00104       axis.axis = -axis.axis;
00105     }
00106     if ((size_t) axis.axis > joy->axes.size())
00107     {return 0;}
00108     return sign * joy->axes[axis.axis - 1] * axis.max;
00109   }
00110 
00111   sensor_msgs::Joy::_buttons_type::value_type getButton(const sensor_msgs::JoyConstPtr &joy, int button)
00112   {
00113     if (button <= 0)
00114     {return 0;}
00115     if ((size_t) button > joy->buttons.size())
00116     {return 0;}
00117     return joy->buttons[button - 1];
00118   }
00119 
00120   void stop()
00121   {
00122     if(velocity_publisher_.getNumSubscribers() > 0)
00123     {
00124       velocity_ = geometry_msgs::Twist();
00125       velocity_publisher_.publish(velocity_);
00126     }
00127   }
00128 };
00129 
00130 int main(int argc, char **argv)
00131 {
00132   ros::init(argc, argv, "quadrotor_teleop");
00133 
00134   Teleop teleop;
00135   ros::spin();
00136 
00137   return 0;
00138 }


crazyflie_demo
Author(s): Wolfgang Hoenig
autogenerated on Sun Oct 8 2017 02:48:01