publish_control.h
Go to the documentation of this file.
1 /*
2 * Unpublished Copyright (c) 2009-2018 AutonomouStuff, LLC, All Rights Reserved.
3 *
4 * This file is part of the PACMod ROS 1.0 driver which is released under the MIT license.
5 * See file LICENSE included with this software or go to https://opensource.org/licenses/MIT for full license details.
6 */
7 
8 #ifndef PUBLISH_CONTROL_H
9 #define PUBLISH_CONTROL_H
10 
11 #include "globals.h"
12 
13 namespace AS
14 {
15 namespace Joystick
16 {
17 
19 {
20  public:
21  // public functions
23  virtual void callback_control(const sensor_msgs::Joy::ConstPtr& msg);
24  static void callback_veh_speed(const pacmod_msgs::VehicleSpeedRpt::ConstPtr& msg);
25  static void callback_pacmod_enable(const std_msgs::Bool::ConstPtr& msg);
26 
27  // public variables
29  static float max_rot_rad;
30  static int vehicle_type;
32  static int board_rev;
33  static double max_veh_speed;
34  static double accel_scale_val;
35  static double brake_scale_val;
36  static double steering_max_speed;
37  static std::unordered_map<JoyAxis, int, EnumHash> axes;
38  static std::unordered_map<JoyButton, int, EnumHash> btns;
39  static pacmod_msgs::VehicleSpeedRpt::ConstPtr last_speed_rpt;
40  static bool pacmod_enable;
41  static bool prev_enable;
42  static bool last_pacmod_state;
43  static bool accel_0_rcvd;
44  static bool brake_0_rcvd;
45  static int headlight_state;
47  static int wiper_state;
48 
49  protected:
50  virtual void check_is_enabled(const sensor_msgs::Joy::ConstPtr& msg);
51 
52  // ROS node handle
54 
55  // ROS publishers
65 
66  // ROS subscribers
70 
71  // state vectors
72  std::vector<float> last_axes;
73  std::vector<int> last_buttons;
74 
75  // Other Variables
76  static bool local_enable;
77  static bool recent_state_change;
79 
80  private:
81  // private functions
82  virtual void publish_steering_message(const sensor_msgs::Joy::ConstPtr& msg) = 0;
83  virtual void publish_turn_signal_message(const sensor_msgs::Joy::ConstPtr& msg) = 0;
84  virtual void publish_shifting_message(const sensor_msgs::Joy::ConstPtr& msg) = 0;
85  virtual void publish_accelerator_message(const sensor_msgs::Joy::ConstPtr& msg) = 0;
86  virtual void publish_brake_message(const sensor_msgs::Joy::ConstPtr& msg) = 0;
87  virtual void publish_lights_horn_wipers_message(const sensor_msgs::Joy::ConstPtr& msg) = 0;
88 };
89 
90 }
91 }
92 
93 #endif
msg
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 pacmod_msgs::VehicleSpeedRpt::ConstPtr last_speed_rpt
virtual void callback_control(const sensor_msgs::Joy::ConstPtr &msg)
static uint8_t state_change_debounce_count
std::vector< int > last_buttons
Definition: globals.h:20
static void callback_pacmod_enable(const std_msgs::Bool::ConstPtr &msg)
static void callback_veh_speed(const pacmod_msgs::VehicleSpeedRpt::ConstPtr &msg)
static std::unordered_map< JoyButton, int, EnumHash > btns
ros::Publisher steering_set_position_with_speed_limit_pub
std::vector< float > last_axes
virtual void publish_lights_horn_wipers_message(const sensor_msgs::Joy::ConstPtr &msg)=0
ros::Publisher accelerator_cmd_pub
ros::Publisher brake_set_position_pub
virtual void publish_brake_message(const sensor_msgs::Joy::ConstPtr &msg)=0
ros::Publisher turn_signal_cmd_pub
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
static std::unordered_map< JoyAxis, int, EnumHash > axes
virtual void publish_accelerator_message(const sensor_msgs::Joy::ConstPtr &msg)=0


pacmod_game_control
Author(s): Joe Driscoll
autogenerated on Thu Jun 6 2019 19:19:40