Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Static Protected Attributes | Private Member Functions | List of all members
AS::Joystick::PublishControl Class Referenceabstract

#include <publish_control.h>

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

Public Member Functions

virtual void callback_control (const sensor_msgs::Joy::ConstPtr &msg)
 
 PublishControl ()
 

Static Public Member Functions

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

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

virtual void check_is_enabled (const sensor_msgs::Joy::ConstPtr &msg)
 

Protected Attributes

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

static bool local_enable = false
 
static bool recent_state_change
 
static uint8_t state_change_debounce_count
 

Private Member Functions

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

Detailed Description

Definition at line 18 of file publish_control.h.

Constructor & Destructor Documentation

PublishControl::PublishControl ( )

Definition at line 34 of file publish_control.cpp.

Member Function Documentation

void PublishControl::callback_control ( const sensor_msgs::Joy::ConstPtr &  msg)
virtual

Definition at line 47 of file publish_control.cpp.

void PublishControl::callback_pacmod_enable ( const std_msgs::Bool::ConstPtr &  msg)
static

Definition at line 89 of file publish_control.cpp.

void PublishControl::callback_veh_speed ( const pacmod_msgs::VehicleSpeedRpt::ConstPtr &  msg)
static

Definition at line 105 of file publish_control.cpp.

void PublishControl::check_is_enabled ( const sensor_msgs::Joy::ConstPtr &  msg)
protectedvirtual

Definition at line 112 of file publish_control.cpp.

virtual void AS::Joystick::PublishControl::publish_accelerator_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatepure virtual
virtual void AS::Joystick::PublishControl::publish_brake_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatepure virtual
virtual void AS::Joystick::PublishControl::publish_lights_horn_wipers_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatepure virtual
virtual void AS::Joystick::PublishControl::publish_shifting_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatepure virtual
virtual void AS::Joystick::PublishControl::publish_steering_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatepure virtual
virtual void AS::Joystick::PublishControl::publish_turn_signal_message ( const sensor_msgs::Joy::ConstPtr &  msg)
privatepure virtual

Member Data Documentation

bool PublishControl::accel_0_rcvd = false
static

Definition at line 43 of file publish_control.h.

double PublishControl::accel_scale_val = 1.0
static

Definition at line 34 of file publish_control.h.

ros::Publisher AS::Joystick::PublishControl::accelerator_cmd_pub
protected

Definition at line 61 of file publish_control.h.

std::unordered_map< JoyAxis, int, EnumHash > PublishControl::axes
static

Definition at line 37 of file publish_control.h.

int PublishControl::board_rev = INVALID
static

Definition at line 32 of file publish_control.h.

bool PublishControl::brake_0_rcvd = false
static

Definition at line 44 of file publish_control.h.

double PublishControl::brake_scale_val = 1.0
static

Definition at line 35 of file publish_control.h.

ros::Publisher AS::Joystick::PublishControl::brake_set_position_pub
protected

Definition at line 63 of file publish_control.h.

std::unordered_map< JoyButton, int, EnumHash > PublishControl::btns
static

Definition at line 38 of file publish_control.h.

GamepadType PublishControl::controller = LOGITECH_F310
static

Definition at line 31 of file publish_control.h.

ros::Publisher AS::Joystick::PublishControl::enable_pub
protected

Definition at line 64 of file publish_control.h.

ros::Subscriber AS::Joystick::PublishControl::enable_sub
protected

Definition at line 69 of file publish_control.h.

ros::Publisher AS::Joystick::PublishControl::headlight_cmd_pub
protected

Definition at line 57 of file publish_control.h.

int PublishControl::headlight_state = 0
static

Definition at line 45 of file publish_control.h.

bool PublishControl::headlight_state_change = false
static

Definition at line 46 of file publish_control.h.

ros::Publisher AS::Joystick::PublishControl::horn_cmd_pub
protected

Definition at line 58 of file publish_control.h.

ros::Subscriber AS::Joystick::PublishControl::joy_sub
protected

Definition at line 67 of file publish_control.h.

std::vector<float> AS::Joystick::PublishControl::last_axes
protected

Definition at line 72 of file publish_control.h.

std::vector<int> AS::Joystick::PublishControl::last_buttons
protected

Definition at line 73 of file publish_control.h.

bool PublishControl::last_pacmod_state = false
static

Definition at line 42 of file publish_control.h.

pacmod_msgs::VehicleSpeedRpt::ConstPtr PublishControl::last_speed_rpt = NULL
static

Definition at line 39 of file publish_control.h.

bool PublishControl::local_enable = false
staticprotected

Definition at line 76 of file publish_control.h.

float PublishControl::max_rot_rad = MAX_ROT_RAD_DEFAULT
static

Definition at line 29 of file publish_control.h.

double PublishControl::max_veh_speed = INVALID
static

Definition at line 33 of file publish_control.h.

ros::NodeHandle AS::Joystick::PublishControl::n
protected

Definition at line 53 of file publish_control.h.

bool PublishControl::pacmod_enable
static

Definition at line 40 of file publish_control.h.

bool PublishControl::prev_enable = false
static

Definition at line 41 of file publish_control.h.

bool AS::Joystick::PublishControl::recent_state_change
staticprotected

Definition at line 77 of file publish_control.h.

ros::Publisher AS::Joystick::PublishControl::shift_cmd_pub
protected

Definition at line 60 of file publish_control.h.

ros::Subscriber AS::Joystick::PublishControl::speed_sub
protected

Definition at line 68 of file publish_control.h.

uint8_t AS::Joystick::PublishControl::state_change_debounce_count
staticprotected

Definition at line 78 of file publish_control.h.

JoyAxis PublishControl::steering_axis = LEFT_STICK_LR
static

Definition at line 28 of file publish_control.h.

double PublishControl::steering_max_speed = INVALID
static

Definition at line 36 of file publish_control.h.

ros::Publisher AS::Joystick::PublishControl::steering_set_position_with_speed_limit_pub
protected

Definition at line 62 of file publish_control.h.

ros::Publisher AS::Joystick::PublishControl::turn_signal_cmd_pub
protected

Definition at line 56 of file publish_control.h.

int PublishControl::vehicle_type = INVALID
static

Definition at line 30 of file publish_control.h.

ros::Publisher AS::Joystick::PublishControl::wiper_cmd_pub
protected

Definition at line 59 of file publish_control.h.

int PublishControl::wiper_state = 0
static

Definition at line 47 of file publish_control.h.


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