| 123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145 |
- // lidascan_ctrl.hpp
- #ifndef LIDAR_SCAN_CONTROLLER_HPP
- #define LIDAR_SCAN_CONTROLLER_HPP
- #include <rclcpp/rclcpp.hpp>
- #include <sensor_msgs/msg/laser_scan.hpp>
- #include <geometry_msgs/msg/twist.hpp>
- #include <visualization_msgs/msg/marker_array.hpp>
- #include "wheelchair_types.hpp"
- #include "recharge_tool.hpp"
- #include <map>
- #include <memory>
- #include <tuple>
- #include <std_msgs/msg/bool.hpp>
- #include <std_msgs/msg/string.hpp>
- #include<sstream>
- class LidarScanController
- {
- public:
- using LaserScan = sensor_msgs::msg::LaserScan;
- using LaserScanSharedPtr = sensor_msgs::msg::LaserScan::SharedPtr;
- LidarScanController(rclcpp::Node *node);
- ~LidarScanController();
- // 初始化
- void initialize();
- // 新增:获取当前检测到的角平分线信息
- std::pair<double, double> getAngleBisectorInfo() const { return {current_angle_bisector_k_, current_angle_bisector_b_}; }
- // 导航控制接口(外部调用)
- void startNavigation();
- void stopNavigation();
- void stopMotion();
- // 充电电压检测接口
- void setChargingVoltage(bool value);
- bool getChargingVoltage() const;
- // 状态查询
- bool isActive() const { return active_; }
- ChargingState getChargingState() const { return charging_state_; };
- void publishStationDetected(bool detected);
- void resetStationDetection();
- private:
- rclcpp::Node *node_;
- // 新增:存储当前角平分线信息
- double current_angle_bisector_k_;
- double current_angle_bisector_b_;
- bool has_angle_bisector_;
- // ROS2 订阅者和发布者
- rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr scan_sub_;
- rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr pub_ctrl_;
- rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr pub_rviz_;
- rclcpp::TimerBase::SharedPtr navigation_timer_;
- rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr pub_filtered_;
- rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr pub_line_;
- rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr pub_station_detected_;
- rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_charging_voltage_;
- rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;//对外
- rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub2_;//对外
- // 状态变量
- bool active_;
- ChargingState charging_state_;
- geometry_msgs::msg::Twist ctrl_twist_;
- rclcpp::Time ctrl_twist_time_;
- rclcpp::Time detect_station_time_;
- bool station_detected_;
- rclcpp::Time last_station_publish_time_;
- // 参数
- ScanFilterParam param_;
- double distance_threshold_;
- int fit_window_size_;
- double fit_residual_threshold_;
- int frame_index_;
- // 充电检测
- bool detect_charging_voltage_;
- rclcpp::Time detect_charging_voltage_time_;
- // ========== 核心算法函数 ==========
- // 激光数据处理
- void processLaserScan(const LaserScanSharedPtr &msg);
- bool processSegmentData(const LaserScanSharedPtr &msg, int begin_index, int end_index);
- void procData(RechargeResult &result);
- // 运动控制算法
- void controlRechargeMotion(const RechargeResult &result);
- // 过滤算法
- void filterScanModify0(LaserScanSharedPtr msg);
- void filterScanModify1(LaserScanSharedPtr msg);
- void filterScanModify2(LaserScanSharedPtr msg);
- void filterScanModify3(LaserScanSharedPtr msg);
- std::pair<int, int> filterScanModify4(LaserScanSharedPtr msg);
- // 坐标转换
- std::map<int, std::pair<double, double>> laserScanToXY(const LaserScanSharedPtr &scan_msg);
- std::map<int, std::pair<double, double>> laserScanToXY1(int begin_index, int end_index,
- const LaserScanSharedPtr &scan_msg);
- // 分段处理算法
- std::vector<std::pair<int, int>> getSections(
- int begin_index, int end_index,
- const LaserScanSharedPtr &msg,
- const std::map<int, std::pair<double, double>> &xy_list);
- std::map<int, std::tuple<int, int, double, double, double, double, double, int>>
- getSegments(const std::map<int, std::pair<double, double>> &xy_points_map);
- std::map<int, std::tuple<int, int, double, double, double, double, double, int>>
- filterSegments(const std::map<int, std::tuple<int, int, double, double, double, double, double, int>> &turn_segments);
- // 可视化
- void publishRechargeVisualization(const RechargeResult &result);
- // ========== 辅助函数 ==========
- void publishFilteredScan(const LaserScanSharedPtr &original_msg,
- const std::vector<float> &filtered_ranges);
- LaserScanSharedPtr resetLaserData(LaserScanSharedPtr msg, int b_index, int e_index);
- bool isValid(float value) const;
- int getFixedIndex(const LaserScanSharedPtr &msg, int i) const;
- int getFixed() const { return 0; }
- Eigen::MatrixXd getPointList(const std::vector<IndexPoint> &points);
- // 定时器回调
- void navigationTimerCallback();
- // 控制发布
- void publishControl();
- //判断误差函数
- bool checkStationAlignment(double dx,double dy,double yaw_diff);
- };
- #endif // LIDAR_SCAN_CONTROLLER_HPP
|