globals.h
Go to the documentation of this file.
00001 /*
00002 * Unpublished Copyright (c) 2009-2018 AutonomouStuff, LLC, All Rights Reserved.
00003 *
00004 * This file is part of the PACMod ROS 1.0 driver which is released under the MIT license.
00005 * See file LICENSE included with this software or go to https://opensource.org/licenses/MIT for full license details.
00006 */
00007 
00008 #ifndef GLOBALS_H
00009 #define GLOBALS_H
00010 
00011 #include <cstdio>
00012 #include <mutex>
00013 #include <unordered_map>
00014 
00015 #include <ros/ros.h>
00016 #include <sensor_msgs/Joy.h>
00017 #include <std_msgs/Bool.h>
00018 #include <pacmod_msgs/VehicleSpeedRpt.h>
00019 
00020 namespace AS
00021 {
00022 namespace Joystick
00023 {
00024 
00025 // Enums
00026 enum ShiftState
00027 {
00028   SHIFT_PARK = 0,
00029   SHIFT_REVERSE = 1,
00030   SHIFT_NEUTRAL = 2,
00031   SHIFT_LOW = 3,
00032   SHIFT_HIGH = 4
00033 };
00034 
00035 enum TurnSignalState
00036 {
00037   SIGNAL_RIGHT,
00038   SIGNAL_OFF,
00039   SIGNAL_LEFT,
00040   SIGNAL_HAZARD
00041 };
00042 
00043 enum GamepadType
00044 {
00045   LOGITECH_F310,
00046   HRI_SAFE_REMOTE,
00047   LOGITECH_G29,
00048   NINTENDO_SWITCH_WIRED_PLUS,
00049   XBOX_ONE
00050 };
00051 
00052 enum VehicleType
00053 {
00054   POLARIS_GEM,
00055   POLARIS_RANGER,
00056   LEXUS_RX_450H,
00057   INTERNATIONAL_PROSTAR,
00058   VEHICLE_4,
00059   VEHICLE_5,
00060   VEHICLE_6
00061 };
00062 
00063 enum JoyAxis
00064 {
00065   LEFT_STICK_UD,
00066   LEFT_STICK_LR,
00067   RIGHT_STICK_UD,
00068   RIGHT_STICK_LR,
00069   DPAD_UD,
00070   DPAD_LR,
00071   LEFT_TRIGGER_AXIS,   // Sometimes button, sometimes axis
00072   RIGHT_TRIGGER_AXIS   // Sometimes button, sometimes axis
00073 };
00074 
00075 enum JoyButton
00076 {
00077   TOP_BTN,
00078   LEFT_BTN,
00079   BOTTOM_BTN,
00080   RIGHT_BTN,
00081   LEFT_BUMPER,
00082   RIGHT_BUMPER,
00083   BACK_SELECT_MINUS,
00084   START_PLUS,
00085   LEFT_TRIGGER_BTN,   // Sometimes button, sometimes axis
00086   RIGHT_TRIGGER_BTN,  // Sometimes button, sometimes axis
00087   LEFT_STICK_PUSH,
00088   RIGHT_STICK_PUSH
00089 };
00090 
00091 struct EnumHash
00092 {
00093   template <typename T>
00094   std::size_t operator()(T t) const
00095   {
00096     return static_cast<std::size_t>(t);
00097   }
00098 };
00099 
00100 // static constants
00101 static const float ROT_RANGE_SCALER_LB = 0.05;
00102 static const float ACCEL_SCALE_FACTOR = 0.6;
00103 static const float ACCEL_OFFSET = 0.21;
00104 static const float STEER_SCALE_FACTOR = 1.5;
00105 static const float STEER_OFFSET = 1.0;
00106 static const float MAX_ROT_RAD_VEHICLE2 = 6.5;
00107 static const float MAX_ROT_RAD_VEHICLE4 = 8.5;
00108 static const float MAX_ROT_RAD_VEHICLE5 = 8.1;
00109 static const float MAX_ROT_RAD_VEHICLE6 = 8.5;
00110 static const float MAX_ROT_RAD_DEFAULT = 10.9956;
00111 static const float AXES_MIN = -1.0;
00112 static const float AXES_MAX = 1.0;
00113 static const uint16_t NUM_WIPER_STATES = 8;
00114 static const uint16_t WIPER_STATE_START_VALUE = 0;
00115 static const uint16_t NUM_HEADLIGHT_STATES = 3;
00116 static const uint16_t HEADLIGHT_STATE_START_VALUE = 0;
00117 static const uint16_t INVALID = -1;
00118 static const uint16_t BUTTON_DOWN = 1;
00119 
00120 // mutex
00121 static std::mutex enable_mutex;
00122 static std::mutex speed_mutex;
00123 static std::mutex state_change_mutex;
00124 static std::mutex shift_mutex;
00125 static std::mutex turn_mutex;
00126 
00127 }
00128 }
00129 
00130 #endif


pacmod_game_control
Author(s): Joe Driscoll
autogenerated on Thu Jun 6 2019 21:10:24