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


elektron_teleop
Author(s): Maciej Stefanczyk
autogenerated on Sun Oct 5 2014 23:43:29