youbot_joy_teleop.h
Go to the documentation of this file.
00001 
00012 #ifndef YOUBOT_JOY_TELEOP_H_
00013 #define YOUBOT_JOY_TELEOP_H_
00014 
00015 #include <geometry_msgs/Twist.h>
00016 #include <ros/ros.h>
00017 #include <sensor_msgs/Joy.h>
00018 
00019 #define MAX_TRANS_VEL .8
00020 #define MAX_ANG_VEL 1.2
00021 
00028 class youbot_joy_teleop
00029 {
00030 public:
00037   youbot_joy_teleop();
00038   void joy_check();
00039 
00040 private:
00046   void joy_cback(const sensor_msgs::Joy::ConstPtr& joy);
00047 
00048   ros::NodeHandle node; 
00050   ros::Publisher cmd_vel; 
00051   ros::Subscriber joy_sub; 
00053   float linear_throttle_factor; 
00054   float angular_throttle_factor; 
00055 };
00056 
00064 int main(int argc, char **argv);
00065 
00066 #endif


youbot_teleop
Author(s): Russell Toris , Graylin Trevor Jay
autogenerated on Mon Oct 6 2014 09:08:50