lidascan_ctrl.hpp 5.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145
  1. // lidascan_ctrl.hpp
  2. #ifndef LIDAR_SCAN_CONTROLLER_HPP
  3. #define LIDAR_SCAN_CONTROLLER_HPP
  4. #include <rclcpp/rclcpp.hpp>
  5. #include <sensor_msgs/msg/laser_scan.hpp>
  6. #include <geometry_msgs/msg/twist.hpp>
  7. #include <visualization_msgs/msg/marker_array.hpp>
  8. #include "wheelchair_types.hpp"
  9. #include "recharge_tool.hpp"
  10. #include <map>
  11. #include <memory>
  12. #include <tuple>
  13. #include <std_msgs/msg/bool.hpp>
  14. #include <std_msgs/msg/string.hpp>
  15. #include<sstream>
  16. class LidarScanController
  17. {
  18. public:
  19. using LaserScan = sensor_msgs::msg::LaserScan;
  20. using LaserScanSharedPtr = sensor_msgs::msg::LaserScan::SharedPtr;
  21. LidarScanController(rclcpp::Node *node);
  22. ~LidarScanController();
  23. // 初始化
  24. void initialize();
  25. // 新增:获取当前检测到的角平分线信息
  26. std::pair<double, double> getAngleBisectorInfo() const { return {current_angle_bisector_k_, current_angle_bisector_b_}; }
  27. // 导航控制接口(外部调用)
  28. void startNavigation();
  29. void stopNavigation();
  30. void stopMotion();
  31. // 充电电压检测接口
  32. void setChargingVoltage(bool value);
  33. bool getChargingVoltage() const;
  34. // 状态查询
  35. bool isActive() const { return active_; }
  36. ChargingState getChargingState() const { return charging_state_; };
  37. void publishStationDetected(bool detected);
  38. void resetStationDetection();
  39. private:
  40. rclcpp::Node *node_;
  41. // 新增:存储当前角平分线信息
  42. double current_angle_bisector_k_;
  43. double current_angle_bisector_b_;
  44. bool has_angle_bisector_;
  45. // ROS2 订阅者和发布者
  46. rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr scan_sub_;
  47. rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr pub_ctrl_;
  48. rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr pub_rviz_;
  49. rclcpp::TimerBase::SharedPtr navigation_timer_;
  50. rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr pub_filtered_;
  51. rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr pub_line_;
  52. rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr pub_station_detected_;
  53. rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_charging_voltage_;
  54. rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;//对外
  55. rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub2_;//对外
  56. // 状态变量
  57. bool active_;
  58. ChargingState charging_state_;
  59. geometry_msgs::msg::Twist ctrl_twist_;
  60. rclcpp::Time ctrl_twist_time_;
  61. rclcpp::Time detect_station_time_;
  62. bool station_detected_;
  63. rclcpp::Time last_station_publish_time_;
  64. // 参数
  65. ScanFilterParam param_;
  66. double distance_threshold_;
  67. int fit_window_size_;
  68. double fit_residual_threshold_;
  69. int frame_index_;
  70. // 充电检测
  71. bool detect_charging_voltage_;
  72. rclcpp::Time detect_charging_voltage_time_;
  73. // ========== 核心算法函数 ==========
  74. // 激光数据处理
  75. void processLaserScan(const LaserScanSharedPtr &msg);
  76. bool processSegmentData(const LaserScanSharedPtr &msg, int begin_index, int end_index);
  77. void procData(RechargeResult &result);
  78. // 运动控制算法
  79. void controlRechargeMotion(const RechargeResult &result);
  80. // 过滤算法
  81. void filterScanModify0(LaserScanSharedPtr msg);
  82. void filterScanModify1(LaserScanSharedPtr msg);
  83. void filterScanModify2(LaserScanSharedPtr msg);
  84. void filterScanModify3(LaserScanSharedPtr msg);
  85. std::pair<int, int> filterScanModify4(LaserScanSharedPtr msg);
  86. // 坐标转换
  87. std::map<int, std::pair<double, double>> laserScanToXY(const LaserScanSharedPtr &scan_msg);
  88. std::map<int, std::pair<double, double>> laserScanToXY1(int begin_index, int end_index,
  89. const LaserScanSharedPtr &scan_msg);
  90. // 分段处理算法
  91. std::vector<std::pair<int, int>> getSections(
  92. int begin_index, int end_index,
  93. const LaserScanSharedPtr &msg,
  94. const std::map<int, std::pair<double, double>> &xy_list);
  95. std::map<int, std::tuple<int, int, double, double, double, double, double, int>>
  96. getSegments(const std::map<int, std::pair<double, double>> &xy_points_map);
  97. std::map<int, std::tuple<int, int, double, double, double, double, double, int>>
  98. filterSegments(const std::map<int, std::tuple<int, int, double, double, double, double, double, int>> &turn_segments);
  99. // 可视化
  100. void publishRechargeVisualization(const RechargeResult &result);
  101. // ========== 辅助函数 ==========
  102. void publishFilteredScan(const LaserScanSharedPtr &original_msg,
  103. const std::vector<float> &filtered_ranges);
  104. LaserScanSharedPtr resetLaserData(LaserScanSharedPtr msg, int b_index, int e_index);
  105. bool isValid(float value) const;
  106. int getFixedIndex(const LaserScanSharedPtr &msg, int i) const;
  107. int getFixed() const { return 0; }
  108. Eigen::MatrixXd getPointList(const std::vector<IndexPoint> &points);
  109. // 定时器回调
  110. void navigationTimerCallback();
  111. // 控制发布
  112. void publishControl();
  113. //判断误差函数
  114. bool checkStationAlignment(double dx,double dy,double yaw_diff);
  115. };
  116. #endif // LIDAR_SCAN_CONTROLLER_HPP