Public Member Functions | Private Member Functions | Private Attributes | List of all members
Joystick Class Reference

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_
 

Detailed Description

Opens, reads from and publishes joystick events.

Definition at line 50 of file joy_node.cpp.

Constructor & Destructor Documentation

◆ Joystick()

Joystick::Joystick ( )
inline

Definition at line 166 of file joy_node.cpp.

Member Function Documentation

◆ diagnostics()

void Joystick::diagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)
inlineprivate

Publishes diagnostics and status.

Definition at line 75 of file joy_node.cpp.

◆ get_dev_by_joy_name()

std::string Joystick::get_dev_by_joy_name ( const std::string &  joy_name)
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.

◆ main()

int Joystick::main ( int  argc,
char **  argv 
)
inline

Opens joystick port, reads from port and publishes while node is active.

Definition at line 203 of file joy_node.cpp.

◆ set_feedback()

void Joystick::set_feedback ( const sensor_msgs::JoyFeedbackArray::ConstPtr &  msg)
inline

Definition at line 169 of file joy_node.cpp.

Member Data Documentation

◆ autorepeat_rate_

double Joystick::autorepeat_rate_
private

Definition at line 61 of file joy_node.cpp.

◆ coalesce_interval_

double Joystick::coalesce_interval_
private

Definition at line 62 of file joy_node.cpp.

◆ deadzone_

double Joystick::deadzone_
private

Definition at line 60 of file joy_node.cpp.

◆ default_trig_val_

bool Joystick::default_trig_val_
private

Definition at line 56 of file joy_node.cpp.

◆ diagnostic_

diagnostic_updater::Updater Joystick::diagnostic_
private

Definition at line 72 of file joy_node.cpp.

◆ event_count_

int Joystick::event_count_
private

Definition at line 63 of file joy_node.cpp.

◆ ff_fd_

int Joystick::ff_fd_
private

Definition at line 68 of file joy_node.cpp.

◆ joy_dev_

std::string Joystick::joy_dev_
private

Definition at line 57 of file joy_node.cpp.

◆ joy_dev_ff_

std::string Joystick::joy_dev_ff_
private

Definition at line 59 of file joy_node.cpp.

◆ joy_dev_name_

std::string Joystick::joy_dev_name_
private

Definition at line 58 of file joy_node.cpp.

◆ joy_effect_

struct ff_effect Joystick::joy_effect_
private

Definition at line 69 of file joy_node.cpp.

◆ lastDiagTime_

double Joystick::lastDiagTime_
private

Definition at line 66 of file joy_node.cpp.

◆ nh_

ros::NodeHandle Joystick::nh_
private

Definition at line 53 of file joy_node.cpp.

◆ open_

bool Joystick::open_
private

Definition at line 54 of file joy_node.cpp.

◆ pub_

ros::Publisher Joystick::pub_
private

Definition at line 65 of file joy_node.cpp.

◆ pub_count_

int Joystick::pub_count_
private

Definition at line 64 of file joy_node.cpp.

◆ sticky_buttons_

bool Joystick::sticky_buttons_
private

Definition at line 55 of file joy_node.cpp.

◆ update_feedback_

bool Joystick::update_feedback_
private

Definition at line 70 of file joy_node.cpp.


The documentation for this class was generated from the following file:


joy
Author(s): Morgan Quigley, Brian Gerkey, Kevin Watts, Blaise Gassend
autogenerated on Mon Feb 28 2022 22:37:01