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

#include <JoystickDemo.h>

Public Member Functions

 JoystickDemo (ros::NodeHandle &node, ros::NodeHandle &priv_nh)
 

Private Types

enum  {
  BTN_PARK = 3, BTN_REVERSE = 1, BTN_NEUTRAL = 2, BTN_DRIVE = 0,
  BTN_ENABLE = 5, BTN_DISABLE = 4, BTN_STEER_MULT_1 = 6, BTN_STEER_MULT_2 = 7,
  BTN_TRUNK_OPEN = 9, BTN_TRUNK_CLOSE = 10, BTN_COUNT_X = 11, BTN_COUNT_D = 12,
  AXIS_THROTTLE = 5, AXIS_BRAKE = 2, AXIS_STEER_1 = 0, AXIS_STEER_2 = 3,
  AXIS_TURN_SIG = 6, AXIS_DOOR_SELECT = 6, AXIS_DOOR_ACTION = 7, AXIS_COUNT_D = 6,
  AXIS_COUNT_X = 8
}
 

Private Member Functions

void cmdCallback (const ros::TimerEvent &event)
 
void recvJoy (const sensor_msgs::Joy::ConstPtr &msg)
 

Private Attributes

bool brake_
 
float brake_gain_
 
bool count_
 
uint8_t counter_
 
JoystickDataStruct data_
 
bool enable_
 
bool ignore_
 
sensor_msgs::Joy joy_
 
float last_steering_filt_output_
 
ros::Publisher pub_brake_
 
ros::Publisher pub_disable_
 
ros::Publisher pub_enable_
 
ros::Publisher pub_gear_
 
ros::Publisher pub_steering_
 
ros::Publisher pub_throttle_
 
ros::Publisher pub_turn_signal_
 
bool shift_
 
bool signal_
 
bool steer_
 
bool strq_
 
ros::Subscriber sub_joy_
 
float svel_
 
bool throttle_
 
float throttle_gain_
 
ros::Timer timer_
 

Detailed Description

Definition at line 62 of file JoystickDemo.h.

Member Enumeration Documentation

anonymous enum
private
Enumerator
BTN_PARK 
BTN_REVERSE 
BTN_NEUTRAL 
BTN_DRIVE 
BTN_ENABLE 
BTN_DISABLE 
BTN_STEER_MULT_1 
BTN_STEER_MULT_2 
BTN_TRUNK_OPEN 
BTN_TRUNK_CLOSE 
BTN_COUNT_X 
BTN_COUNT_D 
AXIS_THROTTLE 
AXIS_BRAKE 
AXIS_STEER_1 
AXIS_STEER_2 
AXIS_TURN_SIG 
AXIS_DOOR_SELECT 
AXIS_DOOR_ACTION 
AXIS_COUNT_D 
AXIS_COUNT_X 

Definition at line 104 of file JoystickDemo.h.

Constructor & Destructor Documentation

JoystickDemo::JoystickDemo ( ros::NodeHandle node,
ros::NodeHandle priv_nh 
)

Definition at line 37 of file JoystickDemo.cpp.

Member Function Documentation

void JoystickDemo::cmdCallback ( const ros::TimerEvent event)
private

Definition at line 108 of file JoystickDemo.cpp.

void JoystickDemo::recvJoy ( const sensor_msgs::Joy::ConstPtr &  msg)
private

Definition at line 193 of file JoystickDemo.cpp.

Member Data Documentation

bool JoystickDemo::brake_
private

Definition at line 80 of file JoystickDemo.h.

float JoystickDemo::brake_gain_
private

Definition at line 87 of file JoystickDemo.h.

bool JoystickDemo::count_
private

Definition at line 93 of file JoystickDemo.h.

uint8_t JoystickDemo::counter_
private

Definition at line 101 of file JoystickDemo.h.

JoystickDataStruct JoystickDemo::data_
private

Definition at line 99 of file JoystickDemo.h.

bool JoystickDemo::enable_
private

Definition at line 92 of file JoystickDemo.h.

bool JoystickDemo::ignore_
private

Definition at line 91 of file JoystickDemo.h.

sensor_msgs::Joy JoystickDemo::joy_
private

Definition at line 100 of file JoystickDemo.h.

float JoystickDemo::last_steering_filt_output_
private

Definition at line 102 of file JoystickDemo.h.

ros::Publisher JoystickDemo::pub_brake_
private

Definition at line 71 of file JoystickDemo.h.

ros::Publisher JoystickDemo::pub_disable_
private

Definition at line 77 of file JoystickDemo.h.

ros::Publisher JoystickDemo::pub_enable_
private

Definition at line 76 of file JoystickDemo.h.

ros::Publisher JoystickDemo::pub_gear_
private

Definition at line 74 of file JoystickDemo.h.

ros::Publisher JoystickDemo::pub_steering_
private

Definition at line 73 of file JoystickDemo.h.

ros::Publisher JoystickDemo::pub_throttle_
private

Definition at line 72 of file JoystickDemo.h.

ros::Publisher JoystickDemo::pub_turn_signal_
private

Definition at line 75 of file JoystickDemo.h.

bool JoystickDemo::shift_
private

Definition at line 83 of file JoystickDemo.h.

bool JoystickDemo::signal_
private

Definition at line 84 of file JoystickDemo.h.

bool JoystickDemo::steer_
private

Definition at line 82 of file JoystickDemo.h.

bool JoystickDemo::strq_
private

Definition at line 94 of file JoystickDemo.h.

ros::Subscriber JoystickDemo::sub_joy_
private

Definition at line 70 of file JoystickDemo.h.

float JoystickDemo::svel_
private

Definition at line 95 of file JoystickDemo.h.

bool JoystickDemo::throttle_
private

Definition at line 81 of file JoystickDemo.h.

float JoystickDemo::throttle_gain_
private

Definition at line 88 of file JoystickDemo.h.

ros::Timer JoystickDemo::timer_
private

Definition at line 98 of file JoystickDemo.h.


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


dbw_fca_joystick_demo
Author(s): Micho Radovnikovich
autogenerated on Wed May 12 2021 02:14:09