#include <JoystickDemo.h>
Definition at line 60 of file JoystickDemo.h.
| anonymous enum  [private] | 
Definition at line 102 of file JoystickDemo.h.
| JoystickDemo::JoystickDemo | ( | ros::NodeHandle & | node, | 
| ros::NodeHandle & | priv_nh | ||
| ) | 
Definition at line 37 of file JoystickDemo.cpp.
| void JoystickDemo::cmdCallback | ( | const ros::TimerEvent & | event | ) |  [private] | 
Definition at line 106 of file JoystickDemo.cpp.
| void JoystickDemo::recvJoy | ( | const sensor_msgs::Joy::ConstPtr & | msg | ) |  [private] | 
Definition at line 189 of file JoystickDemo.cpp.
| bool JoystickDemo::brake_  [private] | 
Definition at line 78 of file JoystickDemo.h.
| float JoystickDemo::brake_gain_  [private] | 
Definition at line 85 of file JoystickDemo.h.
| bool JoystickDemo::count_  [private] | 
Definition at line 91 of file JoystickDemo.h.
| uint8_t JoystickDemo::counter_  [private] | 
Definition at line 99 of file JoystickDemo.h.
| JoystickDataStruct JoystickDemo::data_  [private] | 
Definition at line 97 of file JoystickDemo.h.
| bool JoystickDemo::enable_  [private] | 
Definition at line 90 of file JoystickDemo.h.
| bool JoystickDemo::ignore_  [private] | 
Definition at line 89 of file JoystickDemo.h.
| sensor_msgs::Joy JoystickDemo::joy_  [private] | 
Definition at line 98 of file JoystickDemo.h.
| float JoystickDemo::last_steering_filt_output_  [private] | 
Definition at line 100 of file JoystickDemo.h.
| ros::Publisher JoystickDemo::pub_brake_  [private] | 
Definition at line 69 of file JoystickDemo.h.
| ros::Publisher JoystickDemo::pub_disable_  [private] | 
Definition at line 75 of file JoystickDemo.h.
| ros::Publisher JoystickDemo::pub_enable_  [private] | 
Definition at line 74 of file JoystickDemo.h.
| ros::Publisher JoystickDemo::pub_gear_  [private] | 
Definition at line 72 of file JoystickDemo.h.
| ros::Publisher JoystickDemo::pub_steering_  [private] | 
Definition at line 71 of file JoystickDemo.h.
| ros::Publisher JoystickDemo::pub_throttle_  [private] | 
Definition at line 70 of file JoystickDemo.h.
| ros::Publisher JoystickDemo::pub_turn_signal_  [private] | 
Definition at line 73 of file JoystickDemo.h.
| bool JoystickDemo::shift_  [private] | 
Definition at line 81 of file JoystickDemo.h.
| bool JoystickDemo::signal_  [private] | 
Definition at line 82 of file JoystickDemo.h.
| bool JoystickDemo::steer_  [private] | 
Definition at line 80 of file JoystickDemo.h.
| bool JoystickDemo::strq_  [private] | 
Definition at line 92 of file JoystickDemo.h.
| ros::Subscriber JoystickDemo::sub_joy_  [private] | 
Definition at line 68 of file JoystickDemo.h.
| float JoystickDemo::svel_  [private] | 
Definition at line 93 of file JoystickDemo.h.
| bool JoystickDemo::throttle_  [private] | 
Definition at line 79 of file JoystickDemo.h.
| float JoystickDemo::throttle_gain_  [private] | 
Definition at line 86 of file JoystickDemo.h.
| ros::Timer JoystickDemo::timer_  [private] | 
Definition at line 96 of file JoystickDemo.h.