Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Static Protected Attributes | Private Member Functions
AS::Joystick::PublishControl Class Reference

#include <publish_control.h>

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

List of all members.

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, EnumHash
axes
static int board_rev = INVALID
static bool brake_0_rcvd = false
static double brake_scale_val = 1.0
static std::unordered_map
< JoyButton, int, EnumHash
btns
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

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) [protected, virtual]

Definition at line 112 of file publish_control.cpp.

virtual void AS::Joystick::PublishControl::publish_accelerator_message ( const sensor_msgs::Joy::ConstPtr &  msg) [private, pure virtual]
virtual void AS::Joystick::PublishControl::publish_brake_message ( const sensor_msgs::Joy::ConstPtr &  msg) [private, pure virtual]
virtual void AS::Joystick::PublishControl::publish_lights_horn_wipers_message ( const sensor_msgs::Joy::ConstPtr &  msg) [private, pure virtual]
virtual void AS::Joystick::PublishControl::publish_shifting_message ( const sensor_msgs::Joy::ConstPtr &  msg) [private, pure virtual]
virtual void AS::Joystick::PublishControl::publish_steering_message ( const sensor_msgs::Joy::ConstPtr &  msg) [private, pure virtual]
virtual void AS::Joystick::PublishControl::publish_turn_signal_message ( const sensor_msgs::Joy::ConstPtr &  msg) [private, pure 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.

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.

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.

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.

Definition at line 31 of file publish_control.h.

Definition at line 64 of file publish_control.h.

Definition at line 69 of file publish_control.h.

Definition at line 57 of file publish_control.h.

Definition at line 45 of file publish_control.h.

Definition at line 46 of file publish_control.h.

Definition at line 58 of file publish_control.h.

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 [static, protected]

Definition at line 76 of file publish_control.h.

Definition at line 29 of file publish_control.h.

Definition at line 33 of file publish_control.h.

Definition at line 53 of file publish_control.h.

Definition at line 40 of file publish_control.h.

bool PublishControl::prev_enable = false [static]

Definition at line 41 of file publish_control.h.

Definition at line 77 of file publish_control.h.

Definition at line 60 of file publish_control.h.

Definition at line 68 of file publish_control.h.

Definition at line 78 of file publish_control.h.

Definition at line 28 of file publish_control.h.

Definition at line 36 of file publish_control.h.

Definition at line 62 of file publish_control.h.

Definition at line 56 of file publish_control.h.

Definition at line 30 of file publish_control.h.

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 21:10:24