优化项目结构
This commit is contained in:
48
inc/ArmorDetector.h
Normal file
48
inc/ArmorDetector.h
Normal file
@@ -0,0 +1,48 @@
|
||||
#ifndef ARMORDETECTOR_H
|
||||
#define ARMORDETECTOR_H
|
||||
|
||||
#include <opencv2/opencv.hpp>
|
||||
#include <vector>
|
||||
#include <string>
|
||||
#include "config.h"
|
||||
|
||||
struct LightBar {
|
||||
cv::Point2f center;
|
||||
cv::Size2f size;
|
||||
float angle; // in degrees
|
||||
float angle_rad; // in radians
|
||||
float area;
|
||||
std::vector<cv::Point2f> center_line; // [end1, end2]
|
||||
float center_line_length;
|
||||
std::vector<cv::Point2f> box;
|
||||
};
|
||||
|
||||
struct ArmorPlate {
|
||||
std::string color;
|
||||
cv::Point2f center;
|
||||
double confidence;
|
||||
std::pair<LightBar, LightBar> pair;
|
||||
std::vector<cv::Point2f> corners_2d; // Can be computed later for 3D pose
|
||||
};
|
||||
|
||||
class ArmorDetector {
|
||||
public:
|
||||
ArmorDetector();
|
||||
|
||||
// Main detection function
|
||||
void detect(const cv::Mat& mask, const std::string& target_color,
|
||||
std::vector<LightBar>& valid_light_bars,
|
||||
std::vector<ArmorPlate>& armor_plates);
|
||||
|
||||
private:
|
||||
float angle_threshold_rad;
|
||||
|
||||
// Helper methods
|
||||
std::vector<LightBar> extract_initial_light_bars(const cv::Mat& mask);
|
||||
std::vector<std::vector<cv::Point2f>> merge_nearby_light_bars(const std::vector<LightBar>& initial_light_bars);
|
||||
std::vector<LightBar> filter_valid_light_bars(const std::vector<std::vector<cv::Point2f>>& processed_boxes);
|
||||
std::vector<ArmorPlate> pair_light_bars_to_armor(const std::vector<LightBar>& light_bars, const std::string& target_color);
|
||||
double calculate_iou(const cv::Rect& b1, const cv::Rect& b2);
|
||||
};
|
||||
|
||||
#endif // ARMORDETECTOR_H
|
||||
28
inc/BallisticPredictor.h
Normal file
28
inc/BallisticPredictor.h
Normal file
@@ -0,0 +1,28 @@
|
||||
#ifndef BALLISTICPREDICTOR_H
|
||||
#define BALLISTICPREDICTOR_H
|
||||
|
||||
#include <opencv2/opencv.hpp>
|
||||
|
||||
class BallisticPredictor {
|
||||
public:
|
||||
BallisticPredictor(float bullet_speed = 16.0f);
|
||||
|
||||
// Predict ballistic point considering target movement and flight time
|
||||
cv::Point2f* predict_ballistic_point(const cv::Point2f* predicted_center,
|
||||
const cv::Point2f& img_center,
|
||||
const cv::Point2f& target_speed);
|
||||
|
||||
// Get last ballistic point
|
||||
const cv::Point2f* get_last_ballistic_point() const { return last_ballistic_point; }
|
||||
|
||||
private:
|
||||
float bullet_speed; // Bullet speed (m/s)
|
||||
float armor_half_width; // Armor half width (converted to meters)
|
||||
float armor_half_height; // Armor half height (converted to meters)
|
||||
cv::Point2f* last_ballistic_point; // Last ballistic prediction
|
||||
|
||||
// Calculate distance to target
|
||||
float calculate_distance(const cv::Point2f& armor_center, const cv::Point2f& img_center, float focal_length = 800.0f);
|
||||
};
|
||||
|
||||
#endif // BALLISTICPREDICTOR_H
|
||||
25
inc/Camera.h
Normal file
25
inc/Camera.h
Normal file
@@ -0,0 +1,25 @@
|
||||
#ifndef CAMERA_H
|
||||
#define CAMERA_H
|
||||
|
||||
#include <opencv2/opencv.hpp>
|
||||
#include <string>
|
||||
|
||||
class Camera {
|
||||
public:
|
||||
cv::VideoCapture cap;
|
||||
bool is_opened;
|
||||
std::string target_color;
|
||||
|
||||
Camera(int cam_id = 0, const std::string& target_color = "red");
|
||||
~Camera();
|
||||
|
||||
void set_cam_params();
|
||||
bool read_frame(cv::Mat& frame);
|
||||
void release();
|
||||
bool switch_color(const std::string& target_color);
|
||||
|
||||
private:
|
||||
void set_camera_parameters();
|
||||
};
|
||||
|
||||
#endif // CAMERA_H
|
||||
23
inc/ImagePreprocessor.h
Normal file
23
inc/ImagePreprocessor.h
Normal file
@@ -0,0 +1,23 @@
|
||||
#ifndef IMAGEPREPROCESSOR_H
|
||||
#define IMAGEPREPROCESSOR_H
|
||||
|
||||
#include <opencv2/opencv.hpp>
|
||||
#include <string>
|
||||
|
||||
class ImagePreprocessor {
|
||||
public:
|
||||
ImagePreprocessor();
|
||||
~ImagePreprocessor();
|
||||
|
||||
// Get mask based on target color
|
||||
cv::Mat get_mask(const cv::Mat& frame, const std::string& target_color);
|
||||
|
||||
// Get frame with only the target color
|
||||
cv::Mat get_color_only_frame(const cv::Mat& frame, const std::string& target_color);
|
||||
|
||||
// Combined function to return both mask and color-only frame
|
||||
void process_frame(const cv::Mat& frame, const std::string& target_color,
|
||||
cv::Mat& mask, cv::Mat& color_only_frame);
|
||||
};
|
||||
|
||||
#endif // IMAGEPREPROCESSOR_H
|
||||
26
inc/KalmanFilter.h
Normal file
26
inc/KalmanFilter.h
Normal file
@@ -0,0 +1,26 @@
|
||||
#ifndef KALMANFILTER_H
|
||||
#define KALMANFILTER_H
|
||||
|
||||
#include <opencv2/opencv.hpp>
|
||||
|
||||
class KalmanFilter {
|
||||
public:
|
||||
KalmanFilter();
|
||||
|
||||
void update(const cv::Point2f& measurement);
|
||||
cv::Point2f predict();
|
||||
|
||||
cv::Point2f get_last_measurement() const { return last_measurement; }
|
||||
cv::Point2f get_last_prediction() const { return last_prediction; }
|
||||
bool is_initialized() const { return initialized; }
|
||||
|
||||
private:
|
||||
cv::KalmanFilter kf;
|
||||
bool initialized;
|
||||
cv::Point2f last_measurement;
|
||||
cv::Point2f last_prediction;
|
||||
|
||||
void init_params();
|
||||
};
|
||||
|
||||
#endif // KALMANFILTER_H
|
||||
34
inc/MindVisionCamera.h
Normal file
34
inc/MindVisionCamera.h
Normal file
@@ -0,0 +1,34 @@
|
||||
#ifndef MINDVISION_CAMERA_H
|
||||
#define MINDVISION_CAMERA_H
|
||||
|
||||
#include <opencv2/opencv.hpp>
|
||||
#include <string>
|
||||
|
||||
// MindVision SDK 头文件 - 可能需要根据实际SDK文件调整
|
||||
extern "C" {
|
||||
#include "CameraApi.h" // 这是MindVision SDK的典型头文件
|
||||
}
|
||||
|
||||
class MindVisionCamera {
|
||||
public:
|
||||
int camera_handle; // MindVision SDK中的相机句柄
|
||||
bool is_opened;
|
||||
std::string target_color;
|
||||
int width;
|
||||
int height;
|
||||
int fps;
|
||||
|
||||
MindVisionCamera(int cam_id = 0, const std::string& target_color = "red");
|
||||
~MindVisionCamera();
|
||||
|
||||
void set_cam_params();
|
||||
bool read_frame(cv::Mat& frame);
|
||||
void release();
|
||||
bool switch_color(const std::string& target_color);
|
||||
|
||||
private:
|
||||
void set_camera_parameters();
|
||||
bool initialize_camera(int cam_id);
|
||||
};
|
||||
|
||||
#endif // MINDVISION_CAMERA_H
|
||||
32
inc/TTLCommunicator.h
Normal file
32
inc/TTLCommunicator.h
Normal file
@@ -0,0 +1,32 @@
|
||||
#ifndef TTLCOMMUNICATOR_H
|
||||
#define TTLCOMMUNICATOR_H
|
||||
|
||||
#include <string>
|
||||
|
||||
// Placeholder for TTL communication class
|
||||
// In a real implementation, you would use a C++ serial library like:
|
||||
// - serial (https://github.com/wjwwood/serial)
|
||||
// - Boost.Asio
|
||||
// - or a system-specific approach
|
||||
|
||||
class TTLCommunicator {
|
||||
public:
|
||||
TTLCommunicator(int baudrate = 115200);
|
||||
~TTLCommunicator();
|
||||
|
||||
bool connect();
|
||||
void close();
|
||||
bool send_data(const std::string& data);
|
||||
bool is_connected() const { return connected; }
|
||||
|
||||
private:
|
||||
std::string port_name;
|
||||
int baudrate;
|
||||
bool connected;
|
||||
|
||||
// These would be implemented with actual serial communication code
|
||||
bool open_serial_port();
|
||||
void close_serial_port();
|
||||
};
|
||||
|
||||
#endif // TTLCOMMUNICATOR_H
|
||||
30
inc/Visualizer.h
Normal file
30
inc/Visualizer.h
Normal file
@@ -0,0 +1,30 @@
|
||||
#ifndef VISUALIZER_H
|
||||
#define VISUALIZER_H
|
||||
|
||||
#include <opencv2/opencv.hpp>
|
||||
#include <vector>
|
||||
#include <string>
|
||||
#include "ArmorDetector.h"
|
||||
|
||||
class Visualizer {
|
||||
public:
|
||||
Visualizer();
|
||||
~Visualizer();
|
||||
|
||||
// Draw light bars on frame
|
||||
cv::Mat& draw_light_bars(cv::Mat& frame, const std::vector<LightBar>& light_bars, const std::string& target_color);
|
||||
|
||||
// Draw armor plate on frame
|
||||
cv::Mat& draw_armor_plate(cv::Mat& frame, const ArmorPlate& armor_plate);
|
||||
|
||||
// Draw offset text
|
||||
cv::Mat& draw_offset_text(cv::Mat& frame, const cv::Point2f* display_center, const std::string& target_color, bool is_predicted = false);
|
||||
|
||||
// Draw crosshair at center
|
||||
cv::Mat& draw_crosshair(cv::Mat& frame, const cv::Point2f& center, const cv::Scalar& color = cv::Scalar(0, 255, 0), int size = 10);
|
||||
|
||||
// Draw ballistic point
|
||||
cv::Mat& draw_ballistic_point(cv::Mat& frame, const cv::Point2f* ballistic_point);
|
||||
};
|
||||
|
||||
#endif // VISUALIZER_H
|
||||
42
inc/config.h
Normal file
42
inc/config.h
Normal file
@@ -0,0 +1,42 @@
|
||||
#ifndef CONFIG_H
|
||||
#define CONFIG_H
|
||||
|
||||
#include <opencv2/opencv.hpp>
|
||||
|
||||
// Camera intrinsic parameters (need actual calibration)
|
||||
const cv::Mat CAMERA_MATRIX = (cv::Mat_<float>(3, 3) <<
|
||||
600, 0, 320,
|
||||
0, 600, 240,
|
||||
0, 0, 1);
|
||||
|
||||
const cv::Mat DIST_COEFFS = cv::Mat::zeros(5, 1, CV_32F); // Distortion coefficients (set to 0 for no distortion)
|
||||
|
||||
// Armor dimensions (in mm)
|
||||
const float ARMOR_WIDTH = 135.0f;
|
||||
const float ARMOR_HEIGHT = 125.0f;
|
||||
const float ARMOR_THICKNESS = 20.0f;
|
||||
|
||||
const cv::Mat ARMOR_3D_POINTS = (cv::Mat_<float>(4, 3) <<
|
||||
-ARMOR_WIDTH / 2, -ARMOR_HEIGHT / 2, 0,
|
||||
ARMOR_WIDTH / 2, -ARMOR_HEIGHT / 2, 0,
|
||||
ARMOR_WIDTH / 2, ARMOR_HEIGHT / 2, 0,
|
||||
-ARMOR_WIDTH / 2, ARMOR_HEIGHT / 2, 0);
|
||||
|
||||
// Detection thresholds
|
||||
const float HORIZONTAL_ANGLE_THRESHOLD = 25.0f; // Light bar horizontal angle threshold (degrees)
|
||||
const float HORIZONTAL_ANGLE_THRESHOLD_RAD = HORIZONTAL_ANGLE_THRESHOLD * CV_PI / 180.0f;
|
||||
const float NEARBY_LIGHT_BAR_THRESHOLD = 500.0f; // Light bar merging distance threshold (pixels)
|
||||
const float LIGHT_BAR_IOU_THRESHOLD = 0.05f; // Light bar merging IOU threshold
|
||||
const float ARMOR_DISTANCE_RATIO_MIN = 0.6f; // Armor light bar distance ratio range
|
||||
const float ARMOR_DISTANCE_RATIO_MAX = 3.0f;
|
||||
const float ARMOR_LENGTH_DIFF_RATIO = 0.5f; // Armor light bar length difference ratio
|
||||
const float ARMOR_ANGLE_DIFF_THRESHOLD = 20.0f * CV_PI / 180.0f; // Armor light bar angle difference threshold (radians)
|
||||
|
||||
// Kalman filter parameters
|
||||
const float KF_PROCESS_NOISE = 0.02f; // Process noise covariance
|
||||
const float KF_MEASUREMENT_NOISE = 0.5f; // Measurement noise covariance
|
||||
|
||||
// TTL communication settings
|
||||
const int TTL_BAUDRATE = 115200;
|
||||
|
||||
#endif // CONFIG_H
|
||||
Reference in New Issue
Block a user