00001 #ifndef PACMOD_PACMOD_CORE_H 00002 #define PACMOD_PACMOD_CORE_H 00003 00004 /* 00005 * Unpublished Copyright (c) 2009-2017 AutonomouStuff, LLC, All Rights Reserved. 00006 * 00007 * This file is part of the PACMod ROS 1.0 driver which is released under the MIT license. 00008 * See file LICENSE included with this software or go to https://opensource.org/licenses/MIT for full license details. 00009 */ 00010 00011 #include <sstream> 00012 #include <cstdint> 00013 #include <memory> 00014 #include <string> 00015 #include <vector> 00016 00017 namespace AS 00018 { 00019 namespace Drivers 00020 { 00021 namespace PACMod 00022 { 00023 enum VehicleType 00024 { 00025 POLARIS_GEM, 00026 POLARIS_RANGER, 00027 INTERNATIONAL_PROSTAR_122, 00028 LEXUS_RX_450H 00029 }; 00030 00031 class PacmodTxMsg 00032 { 00033 public: 00034 static std::shared_ptr<PacmodTxMsg> make_message(const int64_t& can_id); 00035 virtual void parse(uint8_t *in) = 0; 00036 }; 00037 00038 // TX Messages 00039 class GlobalRptMsg : 00040 public PacmodTxMsg 00041 { 00042 public: 00043 static const int64_t CAN_ID; 00044 00045 bool enabled; 00046 bool override_active; 00047 bool user_can_timeout; 00048 bool brake_can_timeout; 00049 bool steering_can_timeout; 00050 bool vehicle_can_timeout; 00051 uint16_t user_can_read_errors; 00052 00053 void parse(uint8_t *in); 00054 }; 00055 00056 class VinRptMsg : 00057 public PacmodTxMsg 00058 { 00059 public: 00060 static const int64_t CAN_ID; 00061 00062 std::string mfg_code; 00063 std::string mfg; 00064 char model_year_code; 00065 uint32_t model_year; 00066 uint32_t serial; 00067 00068 void parse(uint8_t *in); 00069 }; 00070 00071 class SystemRptIntMsg : 00072 public PacmodTxMsg 00073 { 00074 public: 00075 uint32_t manual_input; 00076 uint32_t command; 00077 uint32_t output; 00078 00079 void parse(uint8_t *in); 00080 }; 00081 00082 class TurnSignalRptMsg : 00083 public SystemRptIntMsg 00084 { 00085 public: 00086 static const int64_t CAN_ID; 00087 }; 00088 00089 class HeadlightRptMsg : 00090 public SystemRptIntMsg 00091 { 00092 public: 00093 static const int64_t CAN_ID; 00094 }; 00095 00096 class HornRptMsg : 00097 public SystemRptIntMsg 00098 { 00099 public: 00100 static const int64_t CAN_ID; 00101 }; 00102 00103 class WiperRptMsg : 00104 public SystemRptIntMsg 00105 { 00106 public: 00107 static const int64_t CAN_ID; 00108 }; 00109 00110 class ShiftRptMsg : 00111 public SystemRptIntMsg 00112 { 00113 public: 00114 static const int64_t CAN_ID; 00115 }; 00116 00117 class SystemRptFloatMsg : 00118 public PacmodTxMsg 00119 { 00120 public: 00121 double manual_input; 00122 double command; 00123 double output; 00124 00125 void parse(uint8_t *in); 00126 }; 00127 00128 class AccelRptMsg : 00129 public SystemRptFloatMsg 00130 { 00131 public: 00132 static const int64_t CAN_ID; 00133 }; 00134 00135 class SteerRptMsg : 00136 public SystemRptFloatMsg 00137 { 00138 public: 00139 static const int64_t CAN_ID; 00140 }; 00141 00142 class SteerRpt2Msg : 00143 public SystemRptFloatMsg 00144 { 00145 public: 00146 static const int64_t CAN_ID; 00147 }; 00148 00149 class SteerRpt3Msg : 00150 public SystemRptFloatMsg 00151 { 00152 public: 00153 static const int64_t CAN_ID; 00154 }; 00155 00156 class BrakeRptMsg : 00157 public SystemRptFloatMsg 00158 { 00159 public: 00160 static const int64_t CAN_ID; 00161 }; 00162 00163 class VehicleSpeedRptMsg : 00164 public PacmodTxMsg 00165 { 00166 public: 00167 static const int64_t CAN_ID; 00168 00169 double vehicle_speed; 00170 bool vehicle_speed_valid; 00171 uint8_t vehicle_speed_raw[2]; 00172 00173 void parse(uint8_t *in); 00174 }; 00175 00176 class MotorRpt1Msg : 00177 public PacmodTxMsg 00178 { 00179 public: 00180 double current; 00181 double position; 00182 00183 void parse(uint8_t *in); 00184 }; 00185 00186 class BrakeMotorRpt1Msg : 00187 public MotorRpt1Msg 00188 { 00189 public: 00190 static const int64_t CAN_ID; 00191 }; 00192 00193 class SteerMotorRpt1Msg : 00194 public MotorRpt1Msg 00195 { 00196 public: 00197 static const int64_t CAN_ID; 00198 }; 00199 00200 class MotorRpt2Msg : 00201 public PacmodTxMsg 00202 { 00203 public: 00204 double encoder_temp; 00205 double motor_temp; 00206 double velocity; 00207 00208 void parse(uint8_t *in); 00209 }; 00210 00211 class BrakeMotorRpt2Msg : 00212 public MotorRpt2Msg 00213 { 00214 public: 00215 static const int64_t CAN_ID; 00216 }; 00217 00218 class SteerMotorRpt2Msg : 00219 public MotorRpt2Msg 00220 { 00221 public: 00222 static const int64_t CAN_ID; 00223 }; 00224 00225 class MotorRpt3Msg : 00226 public PacmodTxMsg 00227 { 00228 public: 00229 double torque_output; 00230 double torque_input; 00231 00232 void parse(uint8_t *in); 00233 }; 00234 00235 class BrakeMotorRpt3Msg : 00236 public MotorRpt3Msg 00237 { 00238 public: 00239 static const int64_t CAN_ID; 00240 }; 00241 00242 class SteerMotorRpt3Msg : 00243 public MotorRpt3Msg 00244 { 00245 public: 00246 static const int64_t CAN_ID; 00247 }; 00248 00249 class YawRateRptMsg : 00250 public PacmodTxMsg 00251 { 00252 public: 00253 static const int64_t CAN_ID; 00254 00255 double yaw_rate; 00256 00257 void parse(uint8_t *in); 00258 }; 00259 00260 class LatLonHeadingRptMsg : 00261 public PacmodTxMsg 00262 { 00263 public: 00264 static const int64_t CAN_ID; 00265 00266 int latitude_degrees; 00267 uint32_t latitude_minutes; 00268 uint32_t latitude_seconds; 00269 int longitude_degrees; 00270 uint32_t longitude_minutes; 00271 uint32_t longitude_seconds; 00272 double heading; 00273 00274 void parse(uint8_t *in); 00275 }; 00276 00277 class DateTimeRptMsg : 00278 public PacmodTxMsg 00279 { 00280 public: 00281 static const int64_t CAN_ID; 00282 00283 uint32_t year; 00284 uint8_t month; 00285 uint8_t day; 00286 uint8_t hour; 00287 uint8_t minute; 00288 uint8_t second; 00289 00290 void parse(uint8_t *in); 00291 }; 00292 00293 class WheelSpeedRptMsg : 00294 public PacmodTxMsg 00295 { 00296 public: 00297 static const int64_t CAN_ID; 00298 00299 double front_left_wheel_speed; 00300 double front_right_wheel_speed; 00301 double rear_left_wheel_speed; 00302 double rear_right_wheel_speed; 00303 00304 void parse(uint8_t *in); 00305 }; 00306 00307 class SteeringPIDRpt1Msg : 00308 public PacmodTxMsg 00309 { 00310 public: 00311 static const int64_t CAN_ID; 00312 00313 double dt; 00314 double Kp; 00315 double Ki; 00316 double Kd; 00317 00318 void parse(uint8_t *in); 00319 }; 00320 00321 class SteeringPIDRpt2Msg : 00322 public PacmodTxMsg 00323 { 00324 public: 00325 static const int64_t CAN_ID; 00326 00327 double P_term; 00328 double I_term; 00329 double D_term; 00330 double all_terms; 00331 00332 void parse(uint8_t *in); 00333 }; 00334 00335 class SteeringPIDRpt3Msg : 00336 public PacmodTxMsg 00337 { 00338 public: 00339 static const int64_t CAN_ID; 00340 00341 double new_torque; 00342 double str_angle_desired; 00343 double str_angle_actual; 00344 double error; 00345 00346 void parse(uint8_t *in); 00347 }; 00348 00349 class SteeringPIDRpt4Msg : 00350 public PacmodTxMsg 00351 { 00352 public: 00353 static const int64_t CAN_ID; 00354 00355 double angular_velocity; 00356 double angular_acceleration; 00357 00358 void parse(uint8_t *in); 00359 }; 00360 00361 class ParkingBrakeStatusRptMsg : 00362 public PacmodTxMsg 00363 { 00364 public: 00365 static const int64_t CAN_ID; 00366 00367 bool parking_brake_engaged; 00368 00369 void parse(uint8_t *in); 00370 }; 00371 00372 // RX Messages 00373 class PacmodRxMsg 00374 { 00375 public: 00376 std::vector<uint8_t> data; 00377 }; 00378 00379 class GlobalCmdMsg : 00380 public PacmodRxMsg 00381 { 00382 public: 00383 static const int64_t CAN_ID; 00384 00385 void encode(bool enable, bool clear_override, bool ignore_overide); 00386 }; 00387 00388 class TurnSignalCmdMsg : 00389 public PacmodRxMsg 00390 { 00391 public: 00392 static const int64_t CAN_ID; 00393 00394 void encode(uint8_t turn_signal_cmd); 00395 }; 00396 00397 class HeadlightCmdMsg : 00398 public PacmodRxMsg 00399 { 00400 public: 00401 static const int64_t CAN_ID; 00402 00403 void encode(uint8_t headlight_cmd); 00404 }; 00405 00406 class HornCmdMsg : 00407 public PacmodRxMsg 00408 { 00409 public: 00410 static const int64_t CAN_ID; 00411 00412 void encode(uint8_t horn_cmd); 00413 }; 00414 00415 class WiperCmdMsg : 00416 public PacmodRxMsg 00417 { 00418 public: 00419 static const int64_t CAN_ID; 00420 00421 void encode(uint8_t wiper_cmd); 00422 }; 00423 00424 class ShiftCmdMsg : 00425 public PacmodRxMsg 00426 { 00427 public: 00428 static const int64_t CAN_ID; 00429 00430 void encode(uint8_t shift_cmd); 00431 }; 00432 00433 class AccelCmdMsg : 00434 public PacmodRxMsg 00435 { 00436 public: 00437 static const int64_t CAN_ID; 00438 00439 void encode(double accel_cmd); 00440 }; 00441 00442 class SteerCmdMsg : 00443 public PacmodRxMsg 00444 { 00445 public: 00446 static const int64_t CAN_ID; 00447 00448 void encode(double steer_pos, double steer_spd); 00449 }; 00450 00451 class BrakeCmdMsg : 00452 public PacmodRxMsg 00453 { 00454 public: 00455 static const int64_t CAN_ID; 00456 00457 void encode(double brake_cmd); 00458 }; 00459 } // namespace PACMod 00460 } // namespace Drivers 00461 } // namespace AS 00462 00463 #endif // PACMOD_PACMOD_CORE_H