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