Go to the documentation of this file.00001
00002
00003 #include <ros/ros.h>
00004 #include <geometry_msgs/Twist.h>
00005 #include <sensor_msgs/Joy.h>
00006
00007
00008 class TeleopTraxbot{
00009
00010 public:
00011 TeleopTraxbot();
00012
00013 private:
00014 void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
00015
00016 ros::NodeHandle nh_;
00017
00018 double linear_, angular_;
00019 double l_scale_, a_scale_;
00020 ros::Publisher vel_pub_;
00021 ros::Subscriber joy_sub_;
00022
00023 };
00024
00025
00026 TeleopTraxbot::TeleopTraxbot():
00027 linear_(1),
00028 angular_(2)
00029 {
00030 nh_.param("axis_linear", linear_, linear_);
00031 nh_.param("axis_angular", angular_, angular_);
00032 nh_.param("scale_angular", a_scale_, a_scale_);
00033 nh_.param("scale_linear", l_scale_, l_scale_);
00034
00035 vel_pub_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00036 joy_sub_ = nh_.subscribe<sensor_msgs::Joy>("joy_throttle", 10, &TeleopTraxbot::joyCallback, this);
00037 }
00038
00039
00040 void TeleopTraxbot::joyCallback(const sensor_msgs::Joy::ConstPtr& joy){
00041
00042 geometry_msgs::Twist vel;
00043
00044 vel.linear.x = l_scale_ * joy->buttons[8];
00045 if (vel.linear.x==0.0){
00046 vel.linear.x = -l_scale_ * joy->buttons[9];
00047 }
00048
00049 vel.angular.z = a_scale_ * joy->buttons[6];
00050 if (vel.angular.z==0.0){
00051 vel.angular.z = -a_scale_ * joy->buttons[7];
00052 }
00053
00054 vel_pub_.publish(vel);
00055
00056 }
00057
00058 int main(int argc, char** argv){
00059
00060 ros::init(argc, argv, "traxbot_teleop");
00061 TeleopTraxbot teleop_traxbot;
00062
00063 ros::spin();
00064 }