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 <geometry_msgs/Twist.h>
00032 #include <sensor_msgs/Joy.h>
00033 #include "boost/thread/mutex.hpp"
00034 #include "boost/thread/thread.hpp"
00035 #include "ros/console.h"
00036 
00037 class TurtlebotTeleop
00038 {
00039 public:
00040   TurtlebotTeleop();
00041 
00042 private:
00043   void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
00044   void publish();
00045 
00046   ros::NodeHandle ph_, nh_;
00047 
00048   int linear_, angular_, deadman_axis_;
00049   double l_scale_, a_scale_;
00050   ros::Publisher vel_pub_;
00051   ros::Subscriber joy_sub_;
00052 
00053   geometry_msgs::Twist last_published_;
00054   boost::mutex publish_mutex_;
00055   bool deadman_pressed_;
00056   ros::Timer timer_;
00057 
00058 };
00059 
00060 TurtlebotTeleop::TurtlebotTeleop():
00061   ph_("~"),
00062   linear_(1),
00063   angular_(0),
00064   deadman_axis_(4),
00065   l_scale_(0.3),
00066   a_scale_(0.9)
00067 {
00068   ph_.param("axis_linear", linear_, linear_);
00069   ph_.param("axis_angular", angular_, angular_);
00070   ph_.param("axis_deadman", deadman_axis_, deadman_axis_);
00071   ph_.param("scale_angular", a_scale_, a_scale_);
00072   ph_.param("scale_linear", l_scale_, l_scale_);
00073 
00074   vel_pub_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00075   joy_sub_ = nh_.subscribe<sensor_msgs::Joy>("joy", 10, &TurtlebotTeleop::joyCallback, this);
00076 
00077   timer_ = nh_.createTimer(ros::Duration(0.1), boost::bind(&TurtlebotTeleop::publish, this));
00078 }
00079 
00080 void TurtlebotTeleop::joyCallback(const sensor_msgs::Joy::ConstPtr& joy)
00081 { 
00082   geometry_msgs::Twist vel;
00083   vel.angular.z = a_scale_*joy->axes[angular_];
00084   vel.linear.x = l_scale_*joy->axes[linear_];
00085   last_published_ = vel;
00086   deadman_pressed_ = joy->buttons[deadman_axis_];
00087 
00088 }
00089 
00090 void TurtlebotTeleop::publish()
00091 {
00092   boost::mutex::scoped_lock lock(publish_mutex_);
00093 
00094   if (deadman_pressed_)
00095   {
00096     vel_pub_.publish(last_published_);
00097   }
00098 
00099 }
00100 int main(int argc, char** argv)
00101 {
00102   ros::init(argc, argv, "turtlebot_teleop");
00103   TurtlebotTeleop turtlebot_teleop;
00104 
00105   ros::spin();
00106 }