g30esli_ros.h 2.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106
  1. /*
  2. * Copyright 2017-2019 Autoware Foundation. All rights reserved.
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. */
  16. #ifndef G30ESLI_ROS_H
  17. #define G30ESLI_ROS_H
  18. #include <string>
  19. #include <sstream>
  20. #include <ros/ros.h>
  21. #include <std_msgs/Bool.h>
  22. #include <std_msgs/Float32.h>
  23. #include <geometry_msgs/TwistStamped.h>
  24. #include <autoware_msgs/VehicleCmd.h>
  25. #include <autoware_msgs/VehicleStatus.h>
  26. #include <autoware_msgs/Gear.h>
  27. #include <ds4_msgs/DS4.h>
  28. #include "cansend.h"
  29. #include "g30esli.h"
  30. enum struct MODE
  31. {
  32. AUTO,
  33. JOYSTICK,
  34. };
  35. class G30esliROS
  36. {
  37. private:
  38. struct Command
  39. {
  40. bool received = false;
  41. ros::Time time;
  42. ymc::G30esli::Command command;
  43. };
  44. struct Status
  45. {
  46. bool received = false;
  47. ros::Time time;
  48. ymc::G30esli::Status status;
  49. };
  50. ymc::G30esli g30esli_;
  51. Command commands_[2];
  52. Status status_;
  53. unsigned char alive_;
  54. geometry_msgs::TwistStamped current_twist_;
  55. autoware_msgs::VehicleStatus vehicle_status_;
  56. bool reset_command_;
  57. const double stop_keep_secs_, reset_keep_secs_, disable_reset_secs_;
  58. public:
  59. G30esliROS();
  60. ~G30esliROS();
  61. bool openDevice(const std::string& device);
  62. void receiveStatus(const double& steering_offset_deg);
  63. void sendCommand(const MODE& mode);
  64. void updateAutoCommand(const autoware_msgs::VehicleCmd& msg, const bool& engage, const double& steering_offset_deg,
  65. const double& brake_threshold);
  66. void updateJoystickCommand(const ds4_msgs::DS4& msg, const bool& engage, const double& steering_offset_deg);
  67. void updateAliveCounter();
  68. bool checkOverride();
  69. void checkRestart(const MODE& mode);
  70. bool checkTimeout(const MODE& mode, const double& timeout);
  71. bool emergencyStop(const MODE& mode);
  72. std::string dumpDebug(const MODE& mode);
  73. autoware_msgs::VehicleStatus& getVehicleStatus()
  74. {
  75. return vehicle_status_;
  76. }
  77. geometry_msgs::TwistStamped& getCurrentTwist()
  78. {
  79. return current_twist_;
  80. }
  81. double getBatteryCharge()
  82. {
  83. return status_.status.battery.charge;
  84. }
  85. };
  86. #endif