Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
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 }