#include <publish_control.h>
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) |
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 |
Definition at line 18 of file publish_control.h.
PublishControl::PublishControl | ( | ) |
Definition at line 34 of file publish_control.cpp.
|
virtual |
Definition at line 47 of file publish_control.cpp.
|
static |
Definition at line 89 of file publish_control.cpp.
|
static |
Definition at line 105 of file publish_control.cpp.
|
protectedvirtual |
Definition at line 112 of file publish_control.cpp.
|
privatepure virtual |
Implemented in AS::Joystick::PublishControlBoardRev3, and AS::Joystick::PublishControlBoardRev2.
|
privatepure virtual |
Implemented in AS::Joystick::PublishControlBoardRev3, and AS::Joystick::PublishControlBoardRev2.
|
privatepure virtual |
Implemented in AS::Joystick::PublishControlBoardRev3, and AS::Joystick::PublishControlBoardRev2.
|
privatepure virtual |
Implemented in AS::Joystick::PublishControlBoardRev3, and AS::Joystick::PublishControlBoardRev2.
|
privatepure virtual |
Implemented in AS::Joystick::PublishControlBoardRev3, and AS::Joystick::PublishControlBoardRev2.
|
privatepure virtual |
Implemented in AS::Joystick::PublishControlBoardRev3, and AS::Joystick::PublishControlBoardRev2.
|
static |
Definition at line 43 of file publish_control.h.
|
static |
Definition at line 34 of file publish_control.h.
|
protected |
Definition at line 61 of file publish_control.h.
Definition at line 37 of file publish_control.h.
|
static |
Definition at line 32 of file publish_control.h.
|
static |
Definition at line 44 of file publish_control.h.
|
static |
Definition at line 35 of file publish_control.h.
|
protected |
Definition at line 63 of file publish_control.h.
Definition at line 38 of file publish_control.h.
|
static |
Definition at line 31 of file publish_control.h.
|
protected |
Definition at line 64 of file publish_control.h.
|
protected |
Definition at line 69 of file publish_control.h.
|
protected |
Definition at line 57 of file publish_control.h.
|
static |
Definition at line 45 of file publish_control.h.
|
static |
Definition at line 46 of file publish_control.h.
|
protected |
Definition at line 58 of file publish_control.h.
|
protected |
Definition at line 67 of file publish_control.h.
|
protected |
Definition at line 72 of file publish_control.h.
|
protected |
Definition at line 73 of file publish_control.h.
|
static |
Definition at line 42 of file publish_control.h.
|
static |
Definition at line 39 of file publish_control.h.
|
staticprotected |
Definition at line 76 of file publish_control.h.
|
static |
Definition at line 29 of file publish_control.h.
|
static |
Definition at line 33 of file publish_control.h.
|
protected |
Definition at line 53 of file publish_control.h.
|
static |
Definition at line 40 of file publish_control.h.
|
static |
Definition at line 41 of file publish_control.h.
|
staticprotected |
Definition at line 77 of file publish_control.h.
|
protected |
Definition at line 60 of file publish_control.h.
|
protected |
Definition at line 68 of file publish_control.h.
|
staticprotected |
Definition at line 78 of file publish_control.h.
|
static |
Definition at line 28 of file publish_control.h.
|
static |
Definition at line 36 of file publish_control.h.
|
protected |
Definition at line 62 of file publish_control.h.
|
protected |
Definition at line 56 of file publish_control.h.
|
static |
Definition at line 30 of file publish_control.h.
|
protected |
Definition at line 59 of file publish_control.h.
|
static |
Definition at line 47 of file publish_control.h.