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 bool zero_twist_published_;
00057 ros::Timer timer_;
00058
00059 };
00060
00061 TurtlebotTeleop::TurtlebotTeleop():
00062 ph_("~"),
00063 linear_(1),
00064 angular_(0),
00065 deadman_axis_(4),
00066 l_scale_(0.3),
00067 a_scale_(0.9)
00068 {
00069 ph_.param("axis_linear", linear_, linear_);
00070 ph_.param("axis_angular", angular_, angular_);
00071 ph_.param("axis_deadman", deadman_axis_, deadman_axis_);
00072 ph_.param("scale_angular", a_scale_, a_scale_);
00073 ph_.param("scale_linear", l_scale_, l_scale_);
00074
00075 deadman_pressed_ = false;
00076 zero_twist_published_ = false;
00077
00078 vel_pub_ = ph_.advertise<geometry_msgs::Twist>("cmd_vel", 1, true);
00079 joy_sub_ = nh_.subscribe<sensor_msgs::Joy>("joy", 10, &TurtlebotTeleop::joyCallback, this);
00080
00081 timer_ = nh_.createTimer(ros::Duration(0.1), boost::bind(&TurtlebotTeleop::publish, this));
00082 }
00083
00084 void TurtlebotTeleop::joyCallback(const sensor_msgs::Joy::ConstPtr& joy)
00085 {
00086 geometry_msgs::Twist vel;
00087 vel.angular.z = a_scale_*joy->axes[angular_];
00088 vel.linear.x = l_scale_*joy->axes[linear_];
00089 last_published_ = vel;
00090 deadman_pressed_ = joy->buttons[deadman_axis_];
00091 }
00092
00093 void TurtlebotTeleop::publish()
00094 {
00095 boost::mutex::scoped_lock lock(publish_mutex_);
00096
00097 if (deadman_pressed_)
00098 {
00099 vel_pub_.publish(last_published_);
00100 zero_twist_published_=false;
00101 }
00102 else if(!deadman_pressed_ && !zero_twist_published_)
00103 {
00104 vel_pub_.publish(*new geometry_msgs::Twist());
00105 zero_twist_published_=true;
00106 }
00107 }
00108
00109 int main(int argc, char** argv)
00110 {
00111 ros::init(argc, argv, "turtlebot_teleop");
00112 TurtlebotTeleop turtlebot_teleop;
00113
00114 ros::spin();
00115 }