Go to the documentation of this file.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 #ifndef JOYSTICK_HANDLER_H__
00030 #define JOYSTICK_HANDLER_H__
00031
00032 #include <ros/ros.h>
00033
00034 #include <geometry_msgs/Point.h>
00035
00036 #include <sensor_msgs/Joy.h>
00037
00038
00039
00040 namespace vigir_footstep_planning
00041 {
00042 class JoystickHandler
00043 {
00044 public:
00045 JoystickHandler(ros::NodeHandle& nh);
00046 virtual ~JoystickHandler();
00047
00048
00049 void joyCallback(const sensor_msgs::Joy::ConstPtr& last_joy_msg);
00050
00051 void updateJoystickCommands(double elapsed_time_sec, bool& enable, double& d_x, double& d_y, double& d_yaw) const;
00052
00053 typedef boost::shared_ptr<JoystickHandler> Ptr;
00054 typedef boost::shared_ptr<JoystickHandler> ConstPtr;
00055
00056 protected:
00057 void updateJoystickCommand(double elapsed_time_sec, double joy_val, double& val, double min_vel, double max_vel, double min_acc, double max_acc, double sensivity) const;
00058 double convertJoyAxisToAcc(double elapsed_time_sec, double joy_val, double val, double min_vel, double max_vel) const;
00059
00060
00061 ros::Subscriber joy_sub;
00062
00063
00064 geometry_msgs::Point thresh_lin;
00065 geometry_msgs::Point thresh_rot;
00066 geometry_msgs::Point sensivity_lin;
00067 geometry_msgs::Point sensivity_rot;
00068 geometry_msgs::Point limits_min_lin_vel;
00069 geometry_msgs::Point limits_max_lin_vel;
00070 geometry_msgs::Point limits_min_lin_acc;
00071 geometry_msgs::Point limits_max_lin_acc;
00072 geometry_msgs::Point limits_min_rot_vel;
00073 geometry_msgs::Point limits_max_rot_vel;
00074 geometry_msgs::Point limits_min_rot_acc;
00075 geometry_msgs::Point limits_max_rot_acc;
00076
00077
00078 sensor_msgs::Joy::ConstPtr last_joy_msg;
00079 bool enable_generator;
00080 };
00081 }
00082
00083 #endif