Opens, reads from and publishes joystick events. More...
Public Member Functions | |
Joystick () | |
int | main (int argc, char **argv) |
Opens joystick port, reads from port and publishes while node is active. More... | |
void | set_feedback (const sensor_msgs::JoyFeedbackArray::ConstPtr &msg) |
Private Member Functions | |
void | diagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Publishes diagnostics and status. More... | |
std::string | get_dev_by_joy_name (const std::string &joy_name) |
Returns the device path of the first joystick that matches joy_name. If no match is found, an empty string is returned. More... | |
Private Attributes | |
double | autorepeat_rate_ |
double | coalesce_interval_ |
double | deadzone_ |
bool | default_trig_val_ |
diagnostic_updater::Updater | diagnostic_ |
int | event_count_ |
int | ff_fd_ |
std::string | joy_dev_ |
std::string | joy_dev_ff_ |
std::string | joy_dev_name_ |
struct ff_effect | joy_effect_ |
double | lastDiagTime_ |
ros::NodeHandle | nh_ |
bool | open_ |
ros::Publisher | pub_ |
int | pub_count_ |
bool | sticky_buttons_ |
bool | update_feedback_ |
Opens, reads from and publishes joystick events.
Definition at line 50 of file joy_node.cpp.
|
inline |
Definition at line 166 of file joy_node.cpp.
|
inlineprivate |
Publishes diagnostics and status.
Definition at line 75 of file joy_node.cpp.
|
inlineprivate |
Returns the device path of the first joystick that matches joy_name. If no match is found, an empty string is returned.
Definition at line 107 of file joy_node.cpp.
|
inline |
Opens joystick port, reads from port and publishes while node is active.
Definition at line 203 of file joy_node.cpp.
|
inline |
Definition at line 169 of file joy_node.cpp.
|
private |
Definition at line 61 of file joy_node.cpp.
|
private |
Definition at line 62 of file joy_node.cpp.
|
private |
Definition at line 60 of file joy_node.cpp.
|
private |
Definition at line 56 of file joy_node.cpp.
|
private |
Definition at line 72 of file joy_node.cpp.
|
private |
Definition at line 63 of file joy_node.cpp.
|
private |
Definition at line 68 of file joy_node.cpp.
|
private |
Definition at line 57 of file joy_node.cpp.
|
private |
Definition at line 59 of file joy_node.cpp.
|
private |
Definition at line 58 of file joy_node.cpp.
|
private |
Definition at line 69 of file joy_node.cpp.
|
private |
Definition at line 66 of file joy_node.cpp.
|
private |
Definition at line 53 of file joy_node.cpp.
|
private |
Definition at line 54 of file joy_node.cpp.
|
private |
Definition at line 65 of file joy_node.cpp.
|
private |
Definition at line 64 of file joy_node.cpp.
|
private |
Definition at line 55 of file joy_node.cpp.
|
private |
Definition at line 70 of file joy_node.cpp.