g30esli_interface.h 2.0 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485
  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_INTERFACE_H
  17. #define G30ESLI_INTERFACE_H
  18. #include <cmath>
  19. #include <thread>
  20. #include <mutex>
  21. #include <termios.h>
  22. #include <unistd.h>
  23. #include <fcntl.h>
  24. #include "g30esli_ros.h"
  25. class G30esliInterface
  26. {
  27. private:
  28. // ros nodehandle
  29. ros::NodeHandle nh_, private_nh_;
  30. // ros subscriber
  31. ros::Subscriber vehicle_cmd_sub_;
  32. ros::Subscriber ds4_sub_;
  33. ros::Subscriber engage_sub_;
  34. // ros publisher
  35. ros::Publisher vehicle_status_pub_;
  36. ros::Publisher current_twist_pub_;
  37. ros::Publisher battery_pub_;
  38. // ros param
  39. std::string device_;
  40. bool use_ds4_;
  41. bool enable_reverse_motion_;
  42. double steering_offset_deg_;
  43. double command_timeout_;
  44. double brake_threshold_;
  45. // variables
  46. bool engage_;
  47. bool terminate_thread_;
  48. ros::Time engage_start_;
  49. std::thread* thread_read_status_;
  50. std::thread* thread_read_keyboard_;
  51. std::thread* thread_publish_status_;
  52. std::mutex engage_mutex_;
  53. // ymc g30esli ros driver
  54. MODE mode_;
  55. G30esliROS g30esli_ros_;
  56. public:
  57. G30esliInterface();
  58. ~G30esliInterface();
  59. // callbacks
  60. void vehicleCmdCallback(const autoware_msgs::VehicleCmdConstPtr& msg);
  61. void engageCallback(const std_msgs::BoolConstPtr& msg);
  62. void ds4Callback(const ds4_msgs::DS4ConstPtr& msg);
  63. // thread functions
  64. void readKeyboard();
  65. void readStatus();
  66. void publishStatus();
  67. // fucntions
  68. void run();
  69. bool kbhit();
  70. };
  71. #endif