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
00031 #include <ros/ros.h>
00032 #include <geometry_msgs/Twist.h>
00033 #include <sensor_msgs/Joy.h>
00034 #include "boost/thread/mutex.hpp"
00035 #include "boost/thread/thread.hpp"
00036 #include "ros/console.h"
00037
00038 class RochXboxTeleop
00039 {
00040 public:
00041 RochXboxTeleop();
00042
00043 private:
00044 void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
00045 void publish();
00046
00047 ros::NodeHandle ph_, nh_;
00048
00049 int linear_, angular_, deadman_axis_;
00050 int forward_, left_, right_, back_, increase_, reduce_;
00051 double l_scale_, a_scale_, increase_scale_, reduce_scale_;
00052 double linear_speed_, angular_speed_;
00053 ros::Publisher vel_pub_;
00054 ros::Subscriber joy_sub_;
00055
00056 geometry_msgs::Twist last_published_;
00057 boost::mutex publish_mutex_;
00058 bool deadman_pressed_;
00059 bool zero_twist_published_;
00060 ros::Timer timer_;
00061
00062 };
00063
00064 RochXboxTeleop::RochXboxTeleop():
00065 ph_("~"),
00066 linear_(1),
00067 angular_(0),
00068 forward_(3),
00069 back_(0),
00070 left_(2),
00071 right_(1),
00072 increase_(13),
00073 reduce_(14),
00074 increase_scale_(1.1),
00075 reduce_scale_(.9),
00076 deadman_axis_(4),
00077 l_scale_(0.3),
00078 a_scale_(0.9),
00079 linear_speed_(0.5),
00080 angular_speed_(2.5)
00081 {
00082 ph_.param("axis_linear", linear_, linear_);
00083 ph_.param("axis_angular", angular_, angular_);
00084 ph_.param("axis_forward", forward_, forward_);
00085 ph_.param("axis_back", back_, back_);
00086 ph_.param("axis_left", left_, left_);
00087 ph_.param("axis_right", right_, right_);
00088 ph_.param("axis_deadman", deadman_axis_, deadman_axis_);
00089 ph_.param("scale_angular", a_scale_, a_scale_);
00090 ph_.param("scale_linear", l_scale_, l_scale_);
00091 ph_.param("linear_speed", linear_speed_, linear_speed_);
00092 ph_.param("angular_speed", angular_speed_, angular_speed_);
00093
00094 deadman_pressed_ = false;
00095 zero_twist_published_ = false;
00096
00097 vel_pub_ = ph_.advertise<geometry_msgs::Twist>("cmd_vel", 1, true);
00098 joy_sub_ = nh_.subscribe<sensor_msgs::Joy>("joy", 10, &RochXboxTeleop::joyCallback, this);
00099
00100 timer_ = nh_.createTimer(ros::Duration(0.1), boost::bind(&RochXboxTeleop::publish, this));
00101 }
00102
00103 void RochXboxTeleop::joyCallback(const sensor_msgs::Joy::ConstPtr& joy)
00104 {
00105 geometry_msgs::Twist vel;
00106 if( (a_scale_*joy->axes[angular_] != 430) || (l_scale_*joy->axes[linear_] != 255) ){
00107 vel.angular.z = a_scale_*joy->axes[angular_];
00108 vel.linear.x = l_scale_*joy->axes[linear_];
00109 }
00110 if( joy->buttons[increase_]){
00111 linear_speed_ *= increase_scale_;
00112 angular_speed_ *= increase_scale_;
00113 }
00114 if( joy->buttons[reduce_]){
00115 linear_speed_ *= reduce_scale_;
00116 angular_speed_ *= reduce_scale_;
00117 }
00118 if( joy->buttons[forward_]){
00119 vel.angular.z = 0;
00120 vel.linear.x = linear_speed_;
00121 }
00122 if( joy->buttons[back_]){
00123 vel.angular.z = 0;
00124 vel.linear.x = -linear_speed_;
00125 }
00126 if( joy->buttons[left_]){
00127 vel.angular.z = angular_speed_;
00128 vel.linear.x = 0;
00129 }
00130 if( joy->buttons[right_]){
00131 vel.angular.z = -angular_speed_;
00132 vel.linear.x = 0;
00133 }
00134 last_published_ = vel;
00135 deadman_pressed_ = joy->buttons[deadman_axis_];
00136 ROS_INFO_STREAM("current linear speed:"<<linear_speed_<<"\t angular speed:"<<angular_speed_);
00137 }
00138
00139 void RochXboxTeleop::publish()
00140 {
00141 boost::mutex::scoped_lock lock(publish_mutex_);
00142
00143 if (deadman_pressed_)
00144 {
00145 vel_pub_.publish(last_published_);
00146 zero_twist_published_=false;
00147 }
00148 else if(!deadman_pressed_ && !zero_twist_published_)
00149 {
00150 vel_pub_.publish(*new geometry_msgs::Twist());
00151 zero_twist_published_=true;
00152 }
00153 }
00154
00155 int main(int argc, char** argv)
00156 {
00157 ros::init(argc, argv, "roch_teleop");
00158 RochXboxTeleop husky_xbox_teleop;
00159
00160 ros::spin();
00161 }