#include <publish_control_board_rev3.h>
Public Member Functions | |
PublishControlBoardRev3 () | |
Public Member Functions inherited from AS::Joystick::PublishControl | |
virtual void | callback_control (const sensor_msgs::Joy::ConstPtr &msg) |
PublishControl () | |
Static Public Member Functions | |
static void | callback_shift_rpt (const pacmod_msgs::SystemRptInt::ConstPtr &msg) |
static void | callback_turn_rpt (const pacmod_msgs::SystemRptInt::ConstPtr &msg) |
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 | |
static float | last_brake_cmd = 0.0 |
static int | last_shift_cmd = SHIFT_NEUTRAL |
static int | last_turn_cmd = SIGNAL_OFF |
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, 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 |
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) |
Private Attributes | |
ros::Subscriber | shift_sub |
ros::Subscriber | turn_sub |
Additional Inherited Members | |
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 |
Definition at line 25 of file publish_control_board_rev3.h.
PublishControlBoardRev3::PublishControlBoardRev3 | ( | ) |
Definition at line 16 of file publish_control_board_rev3.cpp.
|
static |
Definition at line 35 of file publish_control_board_rev3.cpp.
|
static |
Definition at line 43 of file publish_control_board_rev3.cpp.
|
privatevirtual |
Implements AS::Joystick::PublishControl.
Definition at line 225 of file publish_control_board_rev3.cpp.
|
privatevirtual |
Implements AS::Joystick::PublishControl.
Definition at line 289 of file publish_control_board_rev3.cpp.
|
privatevirtual |
Implements AS::Joystick::PublishControl.
Definition at line 347 of file publish_control_board_rev3.cpp.
|
privatevirtual |
Implements AS::Joystick::PublishControl.
Definition at line 143 of file publish_control_board_rev3.cpp.
|
privatevirtual |
Implements AS::Joystick::PublishControl.
Definition at line 51 of file publish_control_board_rev3.cpp.
|
privatevirtual |
Implements AS::Joystick::PublishControl.
Definition at line 92 of file publish_control_board_rev3.cpp.
|
static |
Definition at line 36 of file publish_control_board_rev3.h.
|
static |
Definition at line 34 of file publish_control_board_rev3.h.
|
static |
Definition at line 35 of file publish_control_board_rev3.h.
|
private |
Definition at line 48 of file publish_control_board_rev3.h.
|
private |
Definition at line 49 of file publish_control_board_rev3.h.