8 #ifndef PUBLISH_CONTROL_H 9 #define PUBLISH_CONTROL_H 37 static std::unordered_map<JoyAxis, int, EnumHash>
axes;
38 static std::unordered_map<JoyButton, int, EnumHash>
btns;
static GamepadType controller
virtual void publish_steering_message(const sensor_msgs::Joy::ConstPtr &msg)=0
virtual void check_is_enabled(const sensor_msgs::Joy::ConstPtr &msg)
static double steering_max_speed
static pacmod_msgs::VehicleSpeedRpt::ConstPtr last_speed_rpt
virtual void callback_control(const sensor_msgs::Joy::ConstPtr &msg)
static uint8_t state_change_debounce_count
ros::Publisher headlight_cmd_pub
static bool pacmod_enable
static int headlight_state
std::vector< int > last_buttons
ros::Subscriber speed_sub
static void callback_pacmod_enable(const std_msgs::Bool::ConstPtr &msg)
static void callback_veh_speed(const pacmod_msgs::VehicleSpeedRpt::ConstPtr &msg)
ros::Subscriber enable_sub
static JoyAxis steering_axis
static std::unordered_map< JoyButton, int, EnumHash > btns
ros::Publisher steering_set_position_with_speed_limit_pub
static double brake_scale_val
std::vector< float > last_axes
virtual void publish_lights_horn_wipers_message(const sensor_msgs::Joy::ConstPtr &msg)=0
static double accel_scale_val
ros::Publisher accelerator_cmd_pub
ros::Publisher brake_set_position_pub
virtual void publish_brake_message(const sensor_msgs::Joy::ConstPtr &msg)=0
static double max_veh_speed
ros::Publisher turn_signal_cmd_pub
ros::Publisher wiper_cmd_pub
static bool headlight_state_change
virtual void publish_turn_signal_message(const sensor_msgs::Joy::ConstPtr &msg)=0
virtual void publish_shifting_message(const sensor_msgs::Joy::ConstPtr &msg)=0
ros::Publisher shift_cmd_pub
static bool last_pacmod_state
static bool recent_state_change
static std::unordered_map< JoyAxis, int, EnumHash > axes
virtual void publish_accelerator_message(const sensor_msgs::Joy::ConstPtr &msg)=0
ros::Publisher enable_pub
ros::Publisher horn_cmd_pub