Public Member Functions | Private Member Functions | List of all members
AS::Joystick::PublishControlBoardRev2 Class Reference

#include <publish_control_board_rev2.h>

Inheritance diagram for AS::Joystick::PublishControlBoardRev2:
Inheritance graph
[legend]

Public Member Functions

 PublishControlBoardRev2 ()
 
- Public Member Functions inherited from AS::Joystick::PublishControl
virtual void callback_control (const sensor_msgs::Joy::ConstPtr &msg)
 
 PublishControl ()
 

Private Member Functions

void publish_accelerator_message (const sensor_msgs::Joy::ConstPtr &msg)
 
void publish_brake_message (const sensor_msgs::Joy::ConstPtr &msg)
 
void publish_lights_horn_wipers_message (const sensor_msgs::Joy::ConstPtr &msg)
 
void publish_shifting_message (const sensor_msgs::Joy::ConstPtr &msg)
 
void publish_steering_message (const sensor_msgs::Joy::ConstPtr &msg)
 
void publish_turn_signal_message (const sensor_msgs::Joy::ConstPtr &msg)
 

Additional Inherited Members

- Static Public Member Functions inherited from AS::Joystick::PublishControl
static void callback_pacmod_enable (const std_msgs::Bool::ConstPtr &msg)
 
static void callback_veh_speed (const pacmod_msgs::VehicleSpeedRpt::ConstPtr &msg)
 
- Static Public Attributes inherited from AS::Joystick::PublishControl
static bool accel_0_rcvd = false
 
static double accel_scale_val = 1.0
 
static std::unordered_map< JoyAxis, int, EnumHashaxes
 
static int board_rev = INVALID
 
static bool brake_0_rcvd = false
 
static double brake_scale_val = 1.0
 
static std::unordered_map< JoyButton, int, EnumHashbtns
 
static GamepadType controller = LOGITECH_F310
 
static int headlight_state = 0
 
static bool headlight_state_change = false
 
static bool last_pacmod_state = false
 
static pacmod_msgs::VehicleSpeedRpt::ConstPtr last_speed_rpt = NULL
 
static float max_rot_rad = MAX_ROT_RAD_DEFAULT
 
static double max_veh_speed = INVALID
 
static bool pacmod_enable
 
static bool prev_enable = false
 
static JoyAxis steering_axis = LEFT_STICK_LR
 
static double steering_max_speed = INVALID
 
static int vehicle_type = INVALID
 
static int wiper_state = 0
 
- Protected Member Functions inherited from AS::Joystick::PublishControl
virtual void check_is_enabled (const sensor_msgs::Joy::ConstPtr &msg)
 
- Protected Attributes inherited from AS::Joystick::PublishControl
ros::Publisher accelerator_cmd_pub
 
ros::Publisher brake_set_position_pub
 
ros::Publisher enable_pub
 
ros::Subscriber enable_sub
 
ros::Publisher headlight_cmd_pub
 
ros::Publisher horn_cmd_pub
 
ros::Subscriber joy_sub
 
std::vector< float > last_axes
 
std::vector< int > last_buttons
 
ros::NodeHandle n
 
ros::Publisher shift_cmd_pub
 
ros::Subscriber speed_sub
 
ros::Publisher steering_set_position_with_speed_limit_pub
 
ros::Publisher turn_signal_cmd_pub
 
ros::Publisher wiper_cmd_pub
 
- Static Protected Attributes inherited from AS::Joystick::PublishControl
static bool local_enable = false
 
static bool recent_state_change
 
static uint8_t state_change_debounce_count
 

Detailed Description

Definition at line 23 of file publish_control_board_rev2.h.

Constructor & Destructor Documentation

PublishControlBoardRev2::PublishControlBoardRev2 ( )

Definition at line 16 of file publish_control_board_rev2.cpp.

Member Function Documentation

void PublishControlBoardRev2::publish_accelerator_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatevirtual

Implements AS::Joystick::PublishControl.

Definition at line 131 of file publish_control_board_rev2.cpp.

void PublishControlBoardRev2::publish_brake_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatevirtual

Implements AS::Joystick::PublishControl.

Definition at line 186 of file publish_control_board_rev2.cpp.

void PublishControlBoardRev2::publish_lights_horn_wipers_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatevirtual

Implements AS::Joystick::PublishControl.

Definition at line 218 of file publish_control_board_rev2.cpp.

void PublishControlBoardRev2::publish_shifting_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatevirtual

Implements AS::Joystick::PublishControl.

Definition at line 96 of file publish_control_board_rev2.cpp.

void PublishControlBoardRev2::publish_steering_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatevirtual

Implements AS::Joystick::PublishControl.

Definition at line 33 of file publish_control_board_rev2.cpp.

void PublishControlBoardRev2::publish_turn_signal_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatevirtual

Implements AS::Joystick::PublishControl.

Definition at line 62 of file publish_control_board_rev2.cpp.


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


pacmod_game_control
Author(s): Joe Driscoll
autogenerated on Thu Jun 6 2019 19:19:40