#include <publish_control.h>
Definition at line 18 of file publish_control.h.
◆ PublishControl()
PublishControl::PublishControl |
( |
| ) |
|
◆ callback_control()
void PublishControl::callback_control |
( |
const sensor_msgs::Joy::ConstPtr & |
msg | ) |
|
|
virtual |
◆ callback_pacmod_enable()
void PublishControl::callback_pacmod_enable |
( |
const std_msgs::Bool::ConstPtr & |
msg | ) |
|
|
static |
◆ callback_veh_speed()
void PublishControl::callback_veh_speed |
( |
const pacmod_msgs::VehicleSpeedRpt::ConstPtr & |
msg | ) |
|
|
static |
◆ check_is_enabled()
void PublishControl::check_is_enabled |
( |
const sensor_msgs::Joy::ConstPtr & |
msg | ) |
|
|
protectedvirtual |
◆ publish_accelerator_message()
virtual void AS::Joystick::PublishControl::publish_accelerator_message |
( |
const sensor_msgs::Joy::ConstPtr & |
msg | ) |
|
|
privatepure virtual |
◆ publish_brake_message()
virtual void AS::Joystick::PublishControl::publish_brake_message |
( |
const sensor_msgs::Joy::ConstPtr & |
msg | ) |
|
|
privatepure virtual |
◆ publish_lights_horn_wipers_message()
virtual void AS::Joystick::PublishControl::publish_lights_horn_wipers_message |
( |
const sensor_msgs::Joy::ConstPtr & |
msg | ) |
|
|
privatepure virtual |
◆ publish_shifting_message()
virtual void AS::Joystick::PublishControl::publish_shifting_message |
( |
const sensor_msgs::Joy::ConstPtr & |
msg | ) |
|
|
privatepure virtual |
◆ publish_steering_message()
virtual void AS::Joystick::PublishControl::publish_steering_message |
( |
const sensor_msgs::Joy::ConstPtr & |
msg | ) |
|
|
privatepure virtual |
◆ publish_turn_signal_message()
virtual void AS::Joystick::PublishControl::publish_turn_signal_message |
( |
const sensor_msgs::Joy::ConstPtr & |
msg | ) |
|
|
privatepure virtual |
◆ accel_0_rcvd
bool PublishControl::accel_0_rcvd = false |
|
static |
◆ accel_scale_val
double PublishControl::accel_scale_val = 1.0 |
|
static |
◆ accelerator_cmd_pub
◆ axes
◆ board_rev
int PublishControl::board_rev = INVALID |
|
static |
◆ brake_0_rcvd
bool PublishControl::brake_0_rcvd = false |
|
static |
◆ brake_scale_val
double PublishControl::brake_scale_val = 1.0 |
|
static |
◆ brake_set_position_pub
◆ btns
◆ controller
◆ enable_pub
◆ enable_sub
◆ headlight_cmd_pub
◆ headlight_state
int PublishControl::headlight_state = 0 |
|
static |
◆ headlight_state_change
bool PublishControl::headlight_state_change = false |
|
static |
◆ horn_cmd_pub
◆ joy_sub
◆ last_axes
std::vector<float> AS::Joystick::PublishControl::last_axes |
|
protected |
◆ last_buttons
std::vector<int> AS::Joystick::PublishControl::last_buttons |
|
protected |
◆ last_pacmod_state
bool PublishControl::last_pacmod_state = false |
|
static |
◆ last_speed_rpt
pacmod_msgs::VehicleSpeedRpt::ConstPtr PublishControl::last_speed_rpt = NULL |
|
static |
◆ local_enable
bool PublishControl::local_enable = false |
|
staticprotected |
◆ max_rot_rad
◆ max_veh_speed
double PublishControl::max_veh_speed = INVALID |
|
static |
◆ pacmod_enable
bool PublishControl::pacmod_enable |
|
static |
◆ prev_enable
bool PublishControl::prev_enable = false |
|
static |
◆ recent_state_change
bool AS::Joystick::PublishControl::recent_state_change |
|
staticprotected |
◆ shift_cmd_pub
◆ speed_sub
◆ state_change_debounce_count
uint8_t AS::Joystick::PublishControl::state_change_debounce_count |
|
staticprotected |
◆ steering_axis
◆ steering_max_speed
double PublishControl::steering_max_speed = INVALID |
|
static |
◆ steering_set_position_with_speed_limit_pub
ros::Publisher AS::Joystick::PublishControl::steering_set_position_with_speed_limit_pub |
|
protected |
◆ turn_signal_cmd_pub
◆ vehicle_type
int PublishControl::vehicle_type = INVALID |
|
static |
◆ wiper_cmd_pub
◆ wiper_state
int PublishControl::wiper_state = 0 |
|
static |
The documentation for this class was generated from the following files: