diff --git a/CMakeLists.txt b/CMakeLists.txt index 8e80351..79257ee 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.22) project(alliance_auto_aim VERSION 0.0.1 LANGUAGES CXX) # 编译选项 -set(CMAKE_CXX_STANDARD 20) +set(CMAKE_CXX_STANDARD 23) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_POSITION_INDEPENDENT_CODE ON) set(CMAKE_EXPORT_COMPILE_COMMANDS ON) diff --git a/configs/example.yaml b/configs/example.yaml index cdeb620..3683855 100644 --- a/configs/example.yaml +++ b/configs/example.yaml @@ -26,19 +26,16 @@ first_tolerance: 100 # 近距离射击容差,degree second_tolerance: 100 # 远距离射击容差,degree judge_distance: 2 #距离判断阈值 -#####-----fire_controller parameters-----##### -control_delay_s: 0.1 - #####-----aiming_solver parameters-----##### yaw_offset: 1.5 # degree pitch_offset: -0.5 # degree -bullet_speed: 26 +bullet_speed: 20 #####-----aime_point_chooser parameters-----##### comming_angle: 60 # degree leaving_angle: 20 # degree #####-----solver parameters-----##### -R_muzzle2camera: -t_muzzle2camera: +# R_muzzle2camera: +# t_muzzle2camera: diff --git a/include/data/time_stamped.hpp b/include/data/time_stamped.hpp index 4ae93dc..7e1e424 100644 --- a/include/data/time_stamped.hpp +++ b/include/data/time_stamped.hpp @@ -23,6 +23,10 @@ struct TimeStamp { inline TimeStamp operator+ (const TimeStamp& other) const noexcept {return TimeStamp{stamp_ + other.stamp_};} inline TimeStamp operator* (const double& ratio) const noexcept {return from_nanosec(stamp_.count() * ratio);} inline TimeStamp operator/ (const double& ratio) const noexcept {return from_nanosec(stamp_.count() / ratio);} + + inline operator std::chrono::steady_clock::time_point() const { + return std::chrono::steady_clock::time_point{stamp_}; +} template static inline TimeStamp from_seconds(const T time){return TimeStamp{std::chrono::seconds(static_cast(time))};} diff --git a/include/interfaces/fire_controller.hpp b/include/interfaces/fire_controller.hpp index 4c5a3e2..c8ca9ef 100644 --- a/include/interfaces/fire_controller.hpp +++ b/include/interfaces/fire_controller.hpp @@ -2,7 +2,6 @@ #include "data/fire_control.hpp" #include "enum/car_id.hpp" -#include #include namespace world_exe::interfaces { @@ -16,16 +15,16 @@ class IFireControl { * @brief 计算云台和发射系统控制量 * * @param time_duration 额外时间差 典型值:当前时刻到当前帧传感器传入内容的时间差 - * @return const data::FireControl + * @return data::FireControl */ - virtual const data::FireControl CalculateTarget(const std::chrono::seconds& time_duration) const = 0; + virtual data::FireControl CalculateTarget(data::TimeStamp const& time_stamp) const = 0; /** * @brief 获取当前火控系统锁定的车辆ID * - * @return const enumeration::CarIDFlag : 火控系统锁定的车辆ID + * @return enumeration::CarIDFlag : 火控系统锁定的车辆ID */ - virtual const enumeration::CarIDFlag GetAttackCarId() const = 0; + virtual enumeration::CarIDFlag GetAttackCarId() const = 0; virtual ~IFireControl() = default; }; diff --git a/include/interfaces/predictor.hpp b/include/interfaces/predictor.hpp index 9824f66..2133e8d 100644 --- a/include/interfaces/predictor.hpp +++ b/include/interfaces/predictor.hpp @@ -27,6 +27,8 @@ class IPredictor { virtual std::shared_ptr Predictor( const data::TimeStamp& time_stamp) const = 0; + // virtual data::TimeStamp GetTimeStamp() const = 0; + virtual ~IPredictor() = default; }; } \ No newline at end of file diff --git a/src/tongji/auto_aim_system.cpp b/src/tongji/auto_aim_system.cpp index ce640c8..b21d418 100644 --- a/src/tongji/auto_aim_system.cpp +++ b/src/tongji/auto_aim_system.cpp @@ -4,9 +4,11 @@ #include #include +#include #include #include #include +#include #include #include "../v1/sync/syncer.hpp" @@ -16,6 +18,7 @@ #include "data/sync_data.hpp" #include "data/time_stamped.hpp" #include "enum/car_id.hpp" +#include "interfaces/armor_in_gimbal_control.hpp" #include "parameters/params_system_v1.hpp" #include "parameters/profile.hpp" #include "tongji/fire_controller/fire_controller.hpp" @@ -23,6 +26,7 @@ #include "tongji/solver/solver.hpp" #include "tongji/state_machine/state_machine.hpp" #include "utils/fps_counter.hpp" +// #include "utils/visualization.hpp" #include "v1/identifier/identifier.hpp" namespace world_exe::tongji { @@ -30,10 +34,12 @@ using namespace std::chrono; class AutoAimSystem::Impl { public: - Impl(const bool& debug) + explicit Impl(const bool& debug) : debug(debug) - , config_path_("/workspaces/src/alliance_ros_auto_aim/alliance_auto_aim/configs/" - "example.yaml") + , config_path_(std::filesystem::path { __FILE__ }.parent_path().parent_path().parent_path() + / "configs" + / "example." + "yaml") , fps_() { identifier_ = std::make_unique( parameters::ParamsForSystemV1::szu_model_path(), @@ -46,8 +52,7 @@ class AutoAimSystem::Impl { state_machine_ = std::make_shared(); fire_controller_ = std::make_unique( config_path_, state_machine_, live_target_manager_); - time_stamp_ = std::chrono::steady_clock::now(); - syncer_ = std::make_unique(seconds(2), 6e-6); + syncer_ = std::make_unique(seconds(2), 6e-6); core::EventBus::Subscript( parameters::ParamsForSystemV1::raw_image_event, @@ -71,13 +76,12 @@ class AutoAimSystem::Impl { if (flag == enumeration::ArmorIdFlag::None) { state_machine_->SetLostState(); + std::println("no armors identified"); return; } // TODO:update invincible_armors - state_machine_->Update(armors_in_image, enumeration::CarIDFlag::None, - std::chrono::duration_cast( - std::chrono::steady_clock::now() - time_stamp_)); + state_machine_->Update(armors_in_image, enumeration::CarIDFlag::None, time_stamp_); // 这里使用 any_clock::now 也可以,但是时间系统的转换和同步我希望是单独的部分 auto [pack, check] = syncer_->get_data(raw.stamp); @@ -100,7 +104,10 @@ class AutoAimSystem::Impl { const auto target_id = state_machine_->GetAllowdToFires(); + // TODO:读编码器还是旋转矩阵? const auto gimbal_yaw = R_camera2gimbal.eulerAngles(2, 1, 0)[0]; + + time_stamp_ = pack.camera_capture_begin_time_stamp; fire_controller_->UpdateGimbalPosition(gimbal_yaw); /// 这里应该有一个线程进行稳定的输出之类的 @@ -108,7 +115,10 @@ class AutoAimSystem::Impl { core::EventBus::Publish( parameters::ParamsForSystemV1::fire_control_event, GetControlCommand()); - time_stamp_ = std::chrono::steady_clock::now(); + + core::EventBus::Publish>( + world_exe::parameters::ParamsForSystemV1::get_lastest_predictor_event, + fire_controller_->GetArmorsToView()); if (!debug) [[likely]] return; @@ -123,7 +133,7 @@ class AutoAimSystem::Impl { parameters::ParamsForSystemV1::tracker_update_event, combined); core::EventBus::Publish( parameters::ParamsForSystemV1::car_tracing_event, state_machine_->GetAllowdToFires()); - // std::cout << "here" << std::endl; + // if (armors_in_image) { // auto visualized = raw.mat.clone(); // util::visualization::draw_armor_in_image(*armors_in_image, visualized); @@ -147,17 +157,18 @@ class AutoAimSystem::Impl { void SetTransfroms(const data::CameraGimbalMuzzleSyncData& data) { syncer_->set_data(data); } + // TODO:时间戳有待fix data::FireControl GetControlCommand() { fire_controller_->GetAttackCarId(); return fire_controller_->CalculateTarget( - std::chrono::duration_cast(std::chrono::steady_clock::now() - time_stamp_)); + data::TimeStamp(steady_clock::now().time_since_epoch())); } private: bool debug; const std::string config_path_; world_exe::util::FpsCounter fps_; - std::chrono::steady_clock::time_point time_stamp_; + data::TimeStamp time_stamp_; std::unique_ptr identifier_; std::unique_ptr pnp_solver_; std::shared_ptr state_machine_; diff --git a/src/tongji/fire_controller/aim_point_chooser.hpp b/src/tongji/fire_controller/aim_point_chooser.hpp index 51e2c71..63e04f5 100644 --- a/src/tongji/fire_controller/aim_point_chooser.hpp +++ b/src/tongji/fire_controller/aim_point_chooser.hpp @@ -1,18 +1,17 @@ #pragma once +#include #include "data/armor_gimbal_control_spacing.hpp" #include "enum/car_id.hpp" #include "util/math.hpp" -#include - namespace world_exe::tongji::fire_control { using CarIDFlag = enumeration::CarIDFlag; class AimPointChooser { public: - AimPointChooser(const std::string& config_path) { + explicit AimPointChooser(const std::string& config_path) { auto yaml = YAML::LoadFile(config_path); comming_angle_ = yaml["comming_angle"].as() / 57.3; // degree to rad leaving_angle_ = yaml["leaving_angle"].as() / 57.3; // degree to rad @@ -20,28 +19,30 @@ class AimPointChooser { std::pair ChooseAimArmor( const Eigen::Vector& ekf_x, - const std::vector armors, const CarIDFlag& single_id) { + std::vector const& armors, const CarIDFlag& single_id) { const auto armor_num = armors.size(); int chosen_id = -1; // 整车旋转中心的球坐标yaw - const auto center_yaw = std::atan2(ekf_x[2], ekf_x[0]); + const auto center_yaw = std::atan2(ekf_x[2], ekf_x[0]); // rad std::vector> delta_angle_list; for (int i = 0; i < armor_num; i++) { auto delta_angle = util::math::clamp_pm_pi( util::math::get_yaw_from_quaternion(armors[i].orientation) - center_yaw); - delta_angle_list.emplace_back(std::make_tuple(i, delta_angle)); + delta_angle_list.emplace_back(i, delta_angle); } - std::sort(delta_angle_list.begin(), delta_angle_list.end(), - [](const auto& a, const auto& b) { return std::get<1>(a) > std::get<1>(b); }); + std::sort( + delta_angle_list.begin(), delta_angle_list.end(), [](const auto& a, const auto& b) { + return std::abs(std::get<1>(a)) < std::abs(std::get<1>(b)); + }); // 不考虑小陀螺 if (std::abs(ekf_x[8]) <= 2 && single_id != CarIDFlag::Outpost) { // 选择在可射击范围内的装甲板 std::vector id_list; for (const auto& [id, delta_angle] : delta_angle_list) { - if (std::abs(delta_angle) > 60 / 57.3) continue; + if (std::abs(delta_angle) > (60 / 57.3)) continue; id_list.emplace_back(id); } @@ -58,11 +59,10 @@ class AimPointChooser { } } else { // 小陀螺 - double coming_angle = (single_id == CarIDFlag::Outpost) ? 70 / 57.3 : comming_angle_; - double leaving_angle = (single_id == CarIDFlag::Outpost) ? 30 / 57.3 : leaving_angle_; + double coming_angle = (single_id == CarIDFlag::Outpost) ? (70 / 57.3) : comming_angle_; + double leaving_angle = (single_id == CarIDFlag::Outpost) ? (30 / 57.3) : leaving_angle_; // 在小陀螺时,一侧的装甲板不断出现,另一侧的装甲板不断消失,显然前者被打中的概率更高 - // for (const auto& [id, delta_angle] : delta_angle_list) { if (std::abs(delta_angle) > coming_angle) continue; if ((ekf_x[7] > 0 && delta_angle < leaving_angle) @@ -76,7 +76,6 @@ class AimPointChooser { if (chosen_id == -1) { return { false, armors[std::get<0>(delta_angle_list.front())] }; } - return { true, armors[chosen_id], diff --git a/src/tongji/fire_controller/aim_solver.hpp b/src/tongji/fire_controller/aim_solver.hpp index cdeeb8f..012fd11 100644 --- a/src/tongji/fire_controller/aim_solver.hpp +++ b/src/tongji/fire_controller/aim_solver.hpp @@ -1,15 +1,20 @@ #pragma once +#include #include +#include #include #include #include +#include +#include #include #include #include "../predictor/car_predictor/car_predictor.hpp" #include "aim_point_chooser.hpp" +#include "data/time_stamped.hpp" #include "tongji/predictor/kalman_filter/extended_kalman_filter.hpp" #include "tongji/predictor/kalman_filter/predict_model.hpp" #include "trajectory.hpp" @@ -20,7 +25,7 @@ struct AimSolution { bool valid; double yaw; double pitch; - Eigen::Vector3d aim_point; // 最终瞄准点(世界坐标 + 装甲板yaw) + Eigen::Vector3d aim_point; double horizon_distance = 0; // 无人机专有 }; @@ -29,7 +34,7 @@ class AimingSolver { using PredictorModel = predictor::EKFModel<11, 4>; using EKF = predictor::ExtendedKalmanFilter; - AimingSolver(const std::string& config_path, const double& gravity = 9.7833) + explicit AimingSolver(const std::string& config_path, const double& gravity = 9.7833) : aim_point_chooser_(std::make_unique(config_path)) , g_(gravity) { @@ -39,34 +44,45 @@ class AimingSolver { bullet_speed_ = yaml["bullet_speed"].as(); } - AimSolution SolveAimSolution(std::shared_ptr snapshot, - data::TimeStamp time_stamp, const double& control_delay_s) { + AimSolution SolveAimSolution(std::shared_ptr const& snapshot, + data::TimeStamp const& time_stamp, std::chrono::milliseconds control_delay) { - // 迭代求解飞行时间 (最多10次,收敛条件:相邻两次fly_time差 <0.001) - double prev_fly_time_s; + // time_stamp.to_seconds(),control_delay); 迭代求解飞行时间 + // (最多10次,收敛条件:相邻两次fly_time差 <0.001) + double prev_fly_time_s = 0; Eigen::Vector3d final_aim_point; TrajectoryResult final_trajectory; bool converged = false; // HACK:不同击打点影响飞行时间的迭代,需要根据整车的状态(转速和坐标)来选择击打点,不得已将指针转换为派生类 auto snapshot_derived = std::dynamic_pointer_cast(snapshot); + if (!snapshot_derived) + throw std::runtime_error("Failed to cast snapshot to CarPredictor. Unexpected object " + "type."); // 预测目标在未来 dt时间后的位置 for (int i = 0; i < 10; ++i) { - const auto& dt = control_delay_s + prev_fly_time_s; + const auto& dt = prev_fly_time_s + (double)(control_delay).count() / 1000.; const auto& armors = snapshot->Predictor(time_stamp + data::TimeStamp::from_seconds(dt)); - const auto& aim_point = SelectPredictedAim(snapshot_derived->GetPredictedX(dt), - armors->GetArmors(snapshot->GetId()), snapshot->GetId()); - if (!aim_point.has_value()) - return { false, std::numeric_limits::quiet_NaN(), - std::numeric_limits::quiet_NaN(), { }, - 0 }; // failed: no valid aim point + const auto& armors_to_view = armors->GetArmors(snapshot->GetId()); + armors_to_view_ = std::make_shared( + armors_to_view, time_stamp + data::TimeStamp::from_seconds(dt)); + + const auto& aim_point = SelectPredictedAim( + snapshot_derived->GetPredictedX(dt), armors_to_view, snapshot->GetId()); + + if (!aim_point.has_value()) { + std::println("no valid aim point"); + continue; + + } // failed: no valid aim point + const auto traj = SolveTrajectory(aim_point.value(), bullet_speed_); - if (!traj.has_value()) - return { false, std::numeric_limits::quiet_NaN(), - std::numeric_limits::quiet_NaN(), { }, - 0 }; // failed: trajectory unsolvable + if (!traj.has_value()) { + std::println("trajectory unsolvable"); + continue; + } if (i > 0 && std::abs(traj->fly_time - prev_fly_time_s) < 0.001) { final_aim_point = *aim_point; @@ -76,21 +92,29 @@ class AimingSolver { } prev_fly_time_s = traj->fly_time; } - if (!converged) + + if (!converged) { + std::println("trajectory diverse"); + return { false, std::numeric_limits::quiet_NaN(), std::numeric_limits::quiet_NaN(), { }, 0 }; // failed: trajectory did not converge + } const auto xyz = final_aim_point; const double yaw = std::atan2(xyz.y(), xyz.x()) + yaw_offset_; - const double pitch = -(final_trajectory.pitch + pitch_offset_); + const double pitch = (final_trajectory.pitch + pitch_offset_); + return { true, yaw, pitch, final_aim_point }; } + auto GetArmorsToView() -> std::shared_ptr { + return armors_to_view_; + } + private: std::optional SelectPredictedAim(const EKF::XVec& ekf_x, const std::vector& armors, const CarIDFlag& id) const { - const auto& [selectable, aim_point_in_gimbal] = aim_point_chooser_->ChooseAimArmor(ekf_x, armors, id); @@ -102,12 +126,18 @@ class AimingSolver { const Eigen::Vector3d& xyz, const double& bullet_speed) const { double d = std::hypot(xyz.x(), xyz.y()); auto result = TrajectorySolver::SolveTrajectory(bullet_speed, d, xyz.z(), g_); + + if (!result.solvable) { + std::println("solve trajectory failed: d={}, z={},speed={}", d, xyz.z(), bullet_speed); + } + return result.solvable ? std::optional { result } : std::nullopt; } double yaw_offset_, pitch_offset_; double bullet_speed_; const double g_; + std::shared_ptr armors_to_view_; std::unique_ptr aim_point_chooser_; }; diff --git a/src/tongji/fire_controller/fire_controller.cpp b/src/tongji/fire_controller/fire_controller.cpp index 1e3a21e..6638259 100644 --- a/src/tongji/fire_controller/fire_controller.cpp +++ b/src/tongji/fire_controller/fire_controller.cpp @@ -3,6 +3,8 @@ #include #include +#include +#include #include #include "../identifier/identified_armor.hpp" @@ -29,80 +31,96 @@ class FireController::Impl { , firable_(false) , aiming_solver_(std::make_unique(config_path)) , fire_decision_(std::make_unique(config_path)) - , state_machine_(state_machine) - , live_target_manager_(live_target_manager) { - - auto yaml = YAML::LoadFile(config_path); - control_delay_s_ = yaml["control_delay_s"].as(); - } - - const data ::FireControl CalculateTarget( - const std::chrono::seconds& time_from_tracker_timepoint) const { + , state_machine_(std::move(state_machine)) + , live_target_manager_(std::move(live_target_manager)) + , control_delay_(100) { } + data ::FireControl CalculateTarget(data::TimeStamp const& time_stamp) const { if (!fire_decision_ || !state_machine_ || !live_target_manager_) return { .fire_allowance = false }; - const auto& lockable_target = state_machine_->GetAllowdToFires(); + const auto& lockable_target = state_machine_->GetAllowdToFires(); + const auto& snapshot_manager = live_target_manager_->GetPredictor(lockable_target); + if (!snapshot_manager) - return data::FireControl { .time_stamp = - data::TimeStamp { time_from_tracker_timepoint }, + return data::FireControl { .time_stamp = data::TimeStamp { time_stamp }, .gimbal_dir = Eigen::Vector3d::Constant(std::numeric_limits::quiet_NaN()), .fire_allowance = false }; - // const auto& armors_in_gimbal = snapshot_manager->Predictor(time_from_tracker_timepoint); // TODO:这里不应该指针转换 - const auto& aim_solution = aiming_solver_->SolveAimSolution( - snapshot_manager, time_from_tracker_timepoint, control_delay_s_); + const auto& aim_solution = + aiming_solver_->SolveAimSolution(snapshot_manager, time_stamp, control_delay_); + armors_to_view_ = aiming_solver_->GetArmorsToView(); + if (!aim_solution.valid) { + std::println("aim solution invalid ,solver failed"); + return data::FireControl { .time_stamp = time_stamp, + .gimbal_dir = Eigen::Vector3d::Constant(std::numeric_limits::quiet_NaN()), + .fire_allowance = false }; + } const auto gimbal_command = GimbalCommand { aim_solution.yaw, aim_solution.pitch }; const auto target_pos = Eigen::Vector3d { aim_solution.aim_point }; - auto fire_command = aim_solution.valid - ? fire_decision_->ShouldFire(gimbal_yaw_, gimbal_command, target_pos) - : false; - firable_ = fire_command; + + auto fire_command = aim_solution.valid + ? fire_decision_->ShouldFire(gimbal_yaw_, gimbal_command, target_pos) + : false; + firable_ = fire_command; data::FireControl result; - result.fire_allowance = fire_command; - result.gimbal_dir << gimbal_command.yaw, gimbal_command.pitch, 0; - result.time_stamp = data::TimeStamp { time_from_tracker_timepoint }; + // result.fire_allowance = fire_command; + result.fire_allowance = true; + + // result.gimbal_dir << gimbal_command.yaw, gimbal_command.pitch, 0; + result.gimbal_dir << cos(gimbal_command.yaw) * cos(gimbal_command.pitch), + sin(gimbal_command.yaw) * cos(gimbal_command.pitch), sin(gimbal_command.pitch); + result.time_stamp = time_stamp; return result; } - const CarIDFlag GetAttackCarId() const { + CarIDFlag GetAttackCarId() const { if (firable_) return locked_target; return CarIDFlag::None; } void UpdateGimbalPosition(const double& gimbal_yaw) { gimbal_yaw_ = gimbal_yaw; }; + auto GetArmorsToView() -> std::shared_ptr { + return armors_to_view_; + } + private: - double control_delay_s_; + std::chrono::milliseconds control_delay_; double gimbal_yaw_; CarIDFlag locked_target; - mutable double firable_; + mutable bool firable_; std::unique_ptr aiming_solver_; std::unique_ptr fire_decision_; std::shared_ptr state_machine_; std::shared_ptr live_target_manager_; + + mutable std::shared_ptr armors_to_view_; }; FireController::FireController(const std::string& config_path, - std::shared_ptr state_machine, - std::shared_ptr live_target_manager) + std::shared_ptr const& state_machine, + std::shared_ptr const& live_target_manager) : pimpl_(std::make_unique(config_path, state_machine, live_target_manager)) { } FireController::~FireController() = default; -const data ::FireControl FireController::CalculateTarget( - const std::chrono::seconds& time_duration) const { - return pimpl_->CalculateTarget(time_duration); +data ::FireControl FireController::CalculateTarget(data::TimeStamp const& time_stamp) const { + return pimpl_->CalculateTarget(time_stamp); } -const CarIDFlag FireController::GetAttackCarId() const { return pimpl_->GetAttackCarId(); } +CarIDFlag FireController::GetAttackCarId() const { return pimpl_->GetAttackCarId(); } void FireController::UpdateGimbalPosition(const double& gimbal_yaw) { return pimpl_->UpdateGimbalPosition(gimbal_yaw); }; +auto FireController::GetArmorsToView() -> std::shared_ptr { + return pimpl_->GetArmorsToView(); +} + } diff --git a/src/tongji/fire_controller/fire_controller.hpp b/src/tongji/fire_controller/fire_controller.hpp index ffa7d15..4038b5b 100644 --- a/src/tongji/fire_controller/fire_controller.hpp +++ b/src/tongji/fire_controller/fire_controller.hpp @@ -1,6 +1,5 @@ #pragma once -#include #include #include "interfaces/car_state.hpp" @@ -12,16 +11,17 @@ namespace world_exe::tongji::fire_control { class FireController final : public interfaces::IFireControl { public: FireController(const std::string& config_path, - std::shared_ptr state_machine, - std::shared_ptr live_target_manager); + std::shared_ptr const& state_machine, + std::shared_ptr const& live_target_manager); ~FireController(); - const data ::FireControl CalculateTarget( - const std::chrono::seconds& time_duration) const override; - const enumeration ::CarIDFlag GetAttackCarId() const override; + data ::FireControl CalculateTarget(data::TimeStamp const& time_stamp) const override; + enumeration ::CarIDFlag GetAttackCarId() const override; void UpdateGimbalPosition(const double& gimbal_yaw); + auto GetArmorsToView() -> std::shared_ptr; + FireController(const FireController&) = delete; FireController& operator=(const FireController&) = delete; FireController(FireController&&) noexcept = default; diff --git a/src/tongji/fire_controller/trajectory.hpp b/src/tongji/fire_controller/trajectory.hpp index 2b9c5e1..7c599d8 100644 --- a/src/tongji/fire_controller/trajectory.hpp +++ b/src/tongji/fire_controller/trajectory.hpp @@ -17,7 +17,7 @@ struct TrajectorySolver { // g 重力加速度,单位:m/s^2 //(g·x²)/(2v₀²)·u² - x·u + (g·x²)/(2v₀²) + y = 0(其中u = tan(θ)) static auto SolveTrajectory(const double& v0, const double& d, const double& h, const double& g) - -> TrajectoryResult const { + -> TrajectoryResult { auto a = g * d * d / (2 * v0 * v0); auto b = -d; auto c = a + h; diff --git a/src/tongji/identifier/armor_filter.hpp b/src/tongji/identifier/armor_filter.hpp index eb46f93..0ab7e66 100644 --- a/src/tongji/identifier/armor_filter.hpp +++ b/src/tongji/identifier/armor_filter.hpp @@ -2,7 +2,6 @@ #include #include -#include #include #include "data/armor_image_spaceing.hpp" @@ -33,7 +32,7 @@ class ArmorFilter { void Update(enumeration::CarIDFlag ids) { invincible_armor_.clear(); for (auto id : util::enumeration::ExpandArmorIdFlags(ids)) { - invincible_armor_.insert(std::move(id)); + invincible_armor_.insert(id); } } diff --git a/src/tongji/identifier/classifier.hpp b/src/tongji/identifier/classifier.hpp index ca8e919..2367c6e 100644 --- a/src/tongji/identifier/classifier.hpp +++ b/src/tongji/identifier/classifier.hpp @@ -13,7 +13,7 @@ namespace world_exe::tongji::identifier { -// TODO:早期代码,和深大模型不适配,需要TODOTODO +// TODO:和深大模型不适配,需要TODOTODO class Classifier final { public: explicit Classifier(const std::string& config_path) { diff --git a/src/tongji/identifier/decider.cpp b/src/tongji/identifier/decider.cpp index 994bf39..6150c4c 100644 --- a/src/tongji/identifier/decider.cpp +++ b/src/tongji/identifier/decider.cpp @@ -20,6 +20,8 @@ class Decider::Impl { const PriorityMap& priority_map = (mode_ == PriorityMode::MODE_ONE) ? mode1 : mode2; std::vector> armors_list; + armors_list.reserve(armors.size()); + for (const auto& armor : armors) { armors_list.emplace_back(armor.id, priority_map.at(armor.id)); } diff --git a/src/tongji/identifier/decider.hpp b/src/tongji/identifier/decider.hpp index 4fef243..a83bc91 100644 --- a/src/tongji/identifier/decider.hpp +++ b/src/tongji/identifier/decider.hpp @@ -22,7 +22,7 @@ enum class ArmorPriority { class Decider { public: - Decider(PriorityMode mode = PriorityMode::MODE_ONE); + explicit Decider(PriorityMode mode = PriorityMode::MODE_ONE); ~Decider(); enumeration::ArmorIdFlag GetBestArmor(std::vector& armors) const; diff --git a/src/tongji/identifier/identifier.cpp b/src/tongji/identifier/identifier.cpp index 2f716f0..42541e5 100644 --- a/src/tongji/identifier/identifier.cpp +++ b/src/tongji/identifier/identifier.cpp @@ -53,8 +53,8 @@ class Identifier::Impl { void SetTargetColor(Color target_color) { target_color_ = target_color; } - const std::tuple, enumeration::CarIDFlag> - Identify(const cv::Mat& bgr_img) { + std::tuple, enumeration::CarIDFlag> Identify( + const cv::Mat& bgr_img) { // 彩色图转灰度图 cv::Mat gray_img; cv::cvtColor(bgr_img, gray_img, cv::COLOR_BGR2GRAY); @@ -201,7 +201,7 @@ class Identifier::Impl { cv::imwrite(img_path, armor_pattern); } - Color GetColor(const cv::Mat& bgr_img, const std::vector& contour) const { + static Color GetColor(const cv::Mat& bgr_img, const std::vector& contour) { int red_sum = 0, blue_sum = 0; for (const auto& point : contour) { @@ -212,8 +212,8 @@ class Identifier::Impl { return blue_sum > red_sum ? Color::blue : Color::red; } - cv::Mat GetPattern(const cv::Mat& bgr_img, const Lightbar& left_lightbar, - const Lightbar& right_lightbar) const { + static cv::Mat GetPattern( + const cv::Mat& bgr_img, const Lightbar& left_lightbar, const Lightbar& right_lightbar) { // 延长灯条获得装甲板角点 // 1.125 = 0.5 * armor_height / lightbar_length = 0.5 * 126mm / 56mm auto tl = left_lightbar.center - left_lightbar.top2bottom * 1.125; @@ -232,13 +232,13 @@ class Identifier::Impl { return bgr_img(roi); } - cv::Point2f GetCenterNorm(const cv::Mat& bgr_img, const cv::Point2f& center) const { + static cv::Point2f GetCenterNorm(const cv::Mat& bgr_img, const cv::Point2f& center) { auto h = bgr_img.rows; auto w = bgr_img.cols; return { center.x / w, center.y / h }; } - bool IsLargeArmor(double armor_ratio, enumeration::ArmorIdFlag armor_id) const { + static bool IsLargeArmor(double armor_ratio, enumeration::ArmorIdFlag armor_id) { /// 优先根据当前armor.ratio判断 /// TODO: 26赛季是否还需要根据比例判断大小装甲?能否根据图案直接判断? diff --git a/src/tongji/identifier/tracker.hpp b/src/tongji/identifier/tracker.hpp index 1db24c9..127b79b 100644 --- a/src/tongji/identifier/tracker.hpp +++ b/src/tongji/identifier/tracker.hpp @@ -1,5 +1,6 @@ #pragma once +#include #include #include @@ -7,6 +8,7 @@ #include #include "armor_filter.hpp" +#include "data/time_stamped.hpp" #include "decider.hpp" #include "enum/armor_id.hpp" #include "identified_armor.hpp" @@ -27,16 +29,18 @@ class Tracker final { public: Tracker() : armor_filter_(std::make_unique()) - , decider_(std::make_unique()) { } + , decider_(std::make_unique()) + , time_stamp_(data::TimeStamp()) { } ~Tracker() = default; auto SelectTrackingTargetID(const std::shared_ptr& armors_in_image, - const enumeration::CarIDFlag& invincible_armors, - const std::chrono::milliseconds& duration_from_last_update) noexcept - -> enumeration::ArmorIdFlag const { + const enumeration::CarIDFlag& invincible_armors, data::TimeStamp const& time_stamp) noexcept + -> enumeration::ArmorIdFlag { + + CheckCameraOffline(time_stamp); + time_stamp_ = time_stamp; - CheckCameraOffline(duration_from_last_update); armor_filter_->Update(invincible_armors); auto filtered_ids = enumeration::ArmorIdFlag::None; @@ -131,9 +135,11 @@ class Tracker final { } } - void CheckCameraOffline(const std::chrono::milliseconds duration_from_last_update) { + void CheckCameraOffline(data::TimeStamp const& time_stamp) { // if (state_ != TrackState::Lost && (duration_from_last_update > timeout_sec_); - if ((duration_from_last_update > timeout_)) { + auto duration_from_last_update = time_stamp - time_stamp_; + if ((duration_from_last_update.to_nanosec() + > (double)std::chrono::duration_cast(timeout_).count())) { SetState(TrackState::Lost); // std::cout << "I am lost QAQ" << std::endl; } @@ -150,6 +156,8 @@ class Tracker final { TrackState state_ = TrackState::Lost; TrackState pre_state_ = TrackState::Lost; + data::TimeStamp time_stamp_; + std::unique_ptr armor_filter_; std::unique_ptr decider_; diff --git a/src/tongji/predictor/car_predictor/car_predictor.hpp b/src/tongji/predictor/car_predictor/car_predictor.hpp index 570e851..be42927 100644 --- a/src/tongji/predictor/car_predictor/car_predictor.hpp +++ b/src/tongji/predictor/car_predictor/car_predictor.hpp @@ -50,7 +50,6 @@ class CarPredictor final : public interfaces::IPredictor { EKF::PMat P0 = model_.GetP0Dig().asDiagonal(); ekf_.emplace(x0, P0, model_); // 初始化滤波器(预测量、预测量协方差) - } const enumeration ::ArmorIdFlag& GetId() const override { return car_id_; } @@ -58,6 +57,7 @@ class CarPredictor final : public interfaces::IPredictor { std ::shared_ptr Predictor( const data ::TimeStamp& time_stamp) const override { const auto ekf_x = this->GetPredictedX((time_stamp - time_stamp_).to_seconds()); + std::vector armors; for (int id = 0; id < model_.GetArmorNum(); id++) { auto angle = util::math::clamp_pm_pi(ekf_x[6] + id * 2 * CV_PI / model_.GetArmorNum()); @@ -69,28 +69,25 @@ class CarPredictor final : public interfaces::IPredictor { armor.orientation = util::math::euler_to_quaternion(angle, 15. / 180. * CV_PI, 0); armors.emplace_back(std::move(armor)); } - return std::make_shared(armors, time_stamp_); + return std::make_shared(armors, time_stamp); } EKF::XVec GetEkfX() const { return ekf_->x; } - auto GetModel() const -> const PredictorModel { return model_; } - auto GetEkf() const -> const EKF { return ekf_.value(); } + auto GetModel() const -> PredictorModel { return model_; } + auto GetEkf() const -> EKF { return ekf_.value(); } - data::TimeStamp LastSeen() const { return time_stamp_; } - - auto GetPredictedXYZAList(const double& dt) -> std::vector const { + auto GetPredictedXYZAList(const double& dt) -> std::vector { const auto [x_n, P_n] = ekf_->PredictOnce(dt); return model_.GetArmorXYZAList(x_n); } - auto GetPredictedX(const double& dt) const -> const EKF::XVec { + auto GetPredictedX(const double& dt) const -> EKF::XVec { const auto& [x_n, P_n] = ekf_->PredictOnce(dt); return x_n; } - void Update(const data::TimeStamp time_stamp, const Eigen::Vector3d& armor_xyz_in_gimbal, + void Update(data::TimeStamp const& time_stamp, const Eigen::Vector3d& armor_xyz_in_gimbal, const Eigen::Vector3d& armor_ypr_in_gimbal, const Eigen::Vector3d& armor_ypd_in_gimbal) { - // 装甲板匹配 int id = model_.MatchArmor( ekf_->x, armor_xyz_in_gimbal, armor_ypr_in_gimbal, armor_ypd_in_gimbal); diff --git a/src/tongji/predictor/car_predictor/car_predictor_manager.cpp b/src/tongji/predictor/car_predictor/car_predictor_manager.cpp index ae0d276..13e7d1a 100644 --- a/src/tongji/predictor/car_predictor/car_predictor_manager.cpp +++ b/src/tongji/predictor/car_predictor/car_predictor_manager.cpp @@ -3,6 +3,7 @@ #include #include #include +#include #include #include "../in_gimbal_control_armor.hpp" @@ -19,7 +20,7 @@ namespace world_exe::tongji::predictor { class CarPredictorManager::Impl { public: - Impl(const std::string& config_path, const double& timeout_sec) + Impl(std::string_view config_path, const double& timeout_sec) : targets_map_() , last_update_timestamp_(data::TimeStamp { }) , config_path_(config_path) { } @@ -34,7 +35,7 @@ class CarPredictorManager::Impl { // if (!predictor->IsConverged()) { // continue; // } - // if (predictor->IsConverged()) + // if (predictor->IsConverged()) { auto spacings = predictor->Predictor(time_stamp); result.insert(result.end(), spacings->GetArmors(id).begin(), @@ -52,10 +53,10 @@ class CarPredictorManager::Impl { if (it == targets_map_.end()) return nullptr; const auto& [id, predictor] = *it; return std::make_shared( - predictor->GetEkf(), predictor->GetModel(), predictor->LastSeen()); + predictor->GetEkf(), predictor->GetModel(), data::TimeStamp { last_update_timestamp_ }); } - void Update(std::shared_ptr data) { + void Update(std::shared_ptr const& data) { last_update_timestamp_ = data->GetTimeStamp(); const Eigen::Affine3d transform = data->GetCameraToWorld(); @@ -81,7 +82,8 @@ class CarPredictorManager::Impl { } } - // std::erase_if(targets_map_, [](const auto& pair) { return pair.second->IsAppeared(); }); + // std::erase_if(targets_map_, [](const auto& pair) { return pair.second->IsAppeared(); + // }); } } @@ -105,7 +107,7 @@ std ::shared_ptr CarPredictorManager::GetPredictor( return pimpl_->GetPredictor(id); } -void CarPredictorManager::Update(std::shared_ptr data) { +void CarPredictorManager::Update(std::shared_ptr const& data) { return pimpl_->Update(data); } diff --git a/src/tongji/predictor/car_predictor/car_predictor_manager.hpp b/src/tongji/predictor/car_predictor/car_predictor_manager.hpp index d6190ba..40ae3b5 100644 --- a/src/tongji/predictor/car_predictor/car_predictor_manager.hpp +++ b/src/tongji/predictor/car_predictor/car_predictor_manager.hpp @@ -11,7 +11,7 @@ namespace world_exe::tongji::predictor { class CarPredictorManager final : public interfaces::ITargetPredictor { public: - CarPredictorManager(const std::string& config_path, const double& timeout_sec = 0.1); + explicit CarPredictorManager(const std::string& config_path, const double& timeout_sec = 0.1); ~CarPredictorManager(); std ::shared_ptr Predict( @@ -19,7 +19,7 @@ class CarPredictorManager final : public interfaces::ITargetPredictor { std ::shared_ptr GetPredictor( const enumeration ::ArmorIdFlag& id) const override; - void Update(std::shared_ptr data); + void Update(std::shared_ptr const& data); CarPredictorManager(const CarPredictorManager&) = delete; CarPredictorManager& operator=(const CarPredictorManager&) = delete; diff --git a/src/tongji/predictor/kalman_filter/extended_kalman_filter.hpp b/src/tongji/predictor/kalman_filter/extended_kalman_filter.hpp index bd95c1c..693752b 100644 --- a/src/tongji/predictor/kalman_filter/extended_kalman_filter.hpp +++ b/src/tongji/predictor/kalman_filter/extended_kalman_filter.hpp @@ -43,7 +43,7 @@ template class ExtendedKalmanFilter { : x(x0) , P(P0) , model_(model) - , I(Eigen::Matrix::Identity()) { + , I(Eigen::Matrix::Identity()) { // data["residual_yaw"] = 0.0; // data["residual_pitch"] = 0.0; // data["residual_distance"] = 0.0; @@ -56,7 +56,7 @@ template class ExtendedKalmanFilter { } // 无副作用,不修改x,仅预测 - auto PredictOnce(const double& dt) const -> const std::pair { + auto PredictOnce(const double& dt) const -> std::pair { const auto A = model_.A(dt); const auto Q = model_.Q(dt); const auto x_n = model_.f(x, dt); @@ -66,13 +66,13 @@ template class ExtendedKalmanFilter { } auto Update(const double& dt, const ZVec& z, const HMat& H, const RMat& R, const int& id) - -> const XVec { + -> XVec { const auto [x_prior, P_prior] = PredictOnce(dt); const ZVec z_prior = model_.h(x_prior, id); const ZVec residual = model_.z_subtract(z, z_prior); - const RMat S = H * P_prior * H.transpose() + R; + const RMat S = H * P_prior * H.transpose() + R; const Eigen::MatrixXd K = P_prior * H.transpose() * S.inverse(); // std::cout << P << "\n" << std::endl; @@ -91,15 +91,15 @@ template class ExtendedKalmanFilter { return x; } - auto IsDiverse() const -> bool const { return CalculateFailureRate() >= max_failure_rate; } + auto IsDiverse() const -> bool { return CalculateFailureRate() >= max_failure_rate; } private: - auto CalculateFailureRate() const -> bool const { + auto CalculateFailureRate() const -> bool { int failures = std::accumulate(recent_nis_failures.begin(), recent_nis_failures.end(), 0); return (double)failures / window_size; } - auto GetRecentNISFailureRate() const -> double const { + auto GetRecentNISFailureRate() const -> double { if (recent_nis_failures.empty()) return 0.0; int recent_failures = diff --git a/src/tongji/predictor/kalman_filter/predict_model.hpp b/src/tongji/predictor/kalman_filter/predict_model.hpp index deed645..4416084 100644 --- a/src/tongji/predictor/kalman_filter/predict_model.hpp +++ b/src/tongji/predictor/kalman_filter/predict_model.hpp @@ -31,17 +31,15 @@ class EKFModel { using QMat = Eigen::Matrix; using HMat = Eigen::Matrix; - EKFModel(const enumeration::CarIDFlag& car_id) + explicit EKFModel(const enumeration::CarIDFlag& car_id) : car_id_(car_id) { - bool is_balance = (car_id == enumeration::CarIDFlag::InfantryIII - || car_id == enumeration::CarIDFlag::InfantryIV - || car_id == enumeration::CarIDFlag::InfantryV); + // bool is_balance = (car_id == enumeration::CarIDFlag::InfantryIII + // || car_id == enumeration::CarIDFlag::InfantryIV + // || car_id == enumeration::CarIDFlag::InfantryV); P0_dig_.resize(11); - if (is_balance) { - P0_dig_ << 1, 64, 1, 64, 1, 64, 0.4, 100, 1, 1, 1; - } else if (car_id == enumeration::CarIDFlag::Outpost) { + if (car_id == enumeration::CarIDFlag::Outpost) { P0_dig_ << 1, 64, 1, 64, 1, 81, 0.4, 100, 1e-4, 0, 0; } else if (car_id == enumeration::CarIDFlag::Base) { P0_dig_ << 1, 64, 1, 64, 1, 64, 0.4, 100, 1e-4, 0, 0; @@ -57,29 +55,26 @@ class EKFModel { radius_ = 0.2; } - if (is_balance) { - armor_num_ = 2; - } else if (car_id == enumeration::CarIDFlag::Outpost - | car_id == enumeration::CarIDFlag::Base) { + if (car_id == enumeration::CarIDFlag::Outpost | car_id == enumeration::CarIDFlag::Base) { armor_num_ = 3; } else { armor_num_ = 4; } } - auto GetP0Dig() const -> const PDig { return P0_dig_; } - auto GetRadius() const -> const double { return radius_; } - auto GetID() const -> const auto { return car_id_; } - auto GetArmorNum() const -> const int { return armor_num_; } + auto GetP0Dig() const -> PDig { return P0_dig_; } + auto GetRadius() const -> double { return radius_; } + auto GetID() const -> auto { return car_id_; } + auto GetArmorNum() const -> int { return armor_num_; } // 防止夹角求和出现异常值 - constexpr auto x_add(const XVec& a, const XVec& b) const -> const auto { + constexpr auto x_add(const XVec& a, const XVec& b) const -> auto { XVec c = a + b; c(6) = util ::math::clamp_pm_pi(c(6)); return c; } - constexpr auto z_substract(const ZVec& a, const ZVec& b) const -> const auto { + constexpr auto z_substract(const ZVec& a, const ZVec& b) const -> auto { auto c = a - b; c(0) = util::math::clamp_pm_pi(c(0)); c(1) = util::math::clamp_pm_pi(c(1)); @@ -87,11 +82,11 @@ class EKFModel { return c; } - auto A(double dt) const -> auto const { + auto A(double dt) const -> auto { // 状态转移矩阵 - AMat _A; + AMat A_mat; // clang-format off - _A<< + A_mat<< 1, dt, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, dt, 0, 0, 0, 0, 0, 0, 0, @@ -104,12 +99,12 @@ class EKFModel { 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1; //clang-format on - return _A; + return A_mat; } // 防止夹角求和出现异常值 - auto f(const XVec& x, const double& dt)const ->const auto{ + auto f(const XVec& x, const double& dt)const -> auto{ XVec x_prior = this->A(dt) * x; x_prior(6) = util::math::clamp_pm_pi(x_prior(6)); return x_prior; @@ -118,7 +113,7 @@ class EKFModel { auto MatchArmor(const XVec& x, const Eigen::Vector3d& armor_xyz_in_gimbal, const Eigen::Vector3d& armor_ypr_in_gimbal, const Eigen::Vector3d& armor_ypd_in_gimbal) const - ->const int { + -> int { const auto& xyza_list = GetArmorXYZAList(x); std::vector> xyza_i_list; @@ -151,7 +146,7 @@ class EKFModel { } // 计算出装甲板中心的坐标(考虑长短轴) - auto h_armor_xyz(const XVec& x, int id) const ->const auto { + auto h_armor_xyz(const XVec& x, int id) const -> auto { auto angle = util::math::clamp_pm_pi(x(6) + id * 2 * CV_PI / armor_num_); auto use_l_h = (armor_num_ == 4) && (id == 1 || id == 3); @@ -163,7 +158,7 @@ class EKFModel { return Eigen::Vector3d { armor_x, armor_y, armor_z }; } - constexpr auto H(const XVec& x, int id) const->HMat const { + constexpr auto H(const XVec& x, int id) const->HMat { auto angle = util::math::clamp_pm_pi(x(6) + id * 2 * CV_PI / armor_num_); auto cos_angle=std::cos(angle); auto sin_angle=std::sin(angle); @@ -205,7 +200,7 @@ class EKFModel { } auto R(const Eigen::Vector3d& armor_xyz_in_gimbal, const Eigen::Vector3d& armor_ypr_in_gimbal, - const Eigen::Vector3d& armor_ypd_in_gimbal, int id) const -> RMat const { + const Eigen::Vector3d& armor_ypd_in_gimbal, int id) const -> RMat { // Eigen::VectorXd R_dig{{4e-3, 4e-3, 1, 9e-2}}; auto center_yaw = std::atan2(armor_xyz_in_gimbal(1), armor_xyz_in_gimbal(0)); auto delta_angle = util::math::clamp_pm_pi(armor_ypr_in_gimbal(0) - center_yaw); @@ -217,7 +212,7 @@ class EKFModel { return R_dig.asDiagonal(); } - auto Q(const double& dt) const -> const auto { + auto Q(const double& dt) const -> auto { // Piecewise White Noise Model // https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python/blob/master/07-Kalman-Filter-Math.ipynb double v1, v2; @@ -235,9 +230,9 @@ class EKFModel { auto c = dt_ * dt_; // 预测过程噪声偏差的方差 - QMat _Q; + QMat Q_mat; // clang-format off - _Q + Q_mat << a * v1, b * v1, 0, 0, 0, 0, 0, 0, 0, 0, 0, b * v1, c * v1, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -251,7 +246,7 @@ class EKFModel { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; // clang-format on - return _Q; + return Q_mat; } Eigen::Vector4d h(const XVec& x, const int& id) const { @@ -270,7 +265,7 @@ class EKFModel { return c; }; - constexpr auto GetArmorXYZAList(const XVec& ekf_x) const -> const auto { + constexpr auto GetArmorXYZAList(const XVec& ekf_x) const -> auto { std::vector _armor_xyza_list; for (int i = 0; i < armor_num_; i++) { diff --git a/src/tongji/solver/reprojection_util.hpp b/src/tongji/solver/reprojection_util.hpp index 109163a..5d97812 100644 --- a/src/tongji/solver/reprojection_util.hpp +++ b/src/tongji/solver/reprojection_util.hpp @@ -21,11 +21,11 @@ class ReprojectionUtil { ReprojectionUtil() = default; ~ReprojectionUtil() = default; - double CalculateReprojectionError(const Eigen::Matrix3d& R_camera2gimbal, + static double CalculateReprojectionError(const Eigen::Matrix3d& R_camera2gimbal, const Eigen::Vector3d& t_gimbal2camera, const world_exe::data::ArmorImageSpacing& armor_in_image, const Eigen::Vector3d& armor_xyz_in_gimbal, const double& armor_yaw, - const double& armor_pitch, const double& inclined) const { + const double& armor_pitch, const double& inclined) { auto image_points = ReprojectArmor(R_camera2gimbal, t_gimbal2camera, armor_xyz_in_gimbal, armor_yaw, armor_pitch, armor_in_image.isLargeArmor); @@ -41,9 +41,9 @@ class ReprojectionUtil { } private: - std::vector ReprojectArmor(const Eigen::Matrix3d& R_camera2gimbal, + static std::vector ReprojectArmor(const Eigen::Matrix3d& R_camera2gimbal, const Eigen::Vector3d& t_gimbal2camera, const Eigen::Vector3d& armor_xyz_in_gimbal, - const double& armor_yaw, const double& armor_pitch, const bool& is_large) const { + const double& armor_yaw, const double& armor_pitch, const bool& is_large) { auto sin_yaw = std::sin(armor_yaw); auto cos_yaw = std::cos(armor_yaw); @@ -69,9 +69,9 @@ class ReprojectionUtil { // get rvec tvec cv::Vec3d rvec; - cv::Mat _R_armor2camera_cv; - cv::eigen2cv(R_armor2camera_cv, _R_armor2camera_cv); - cv::Rodrigues(_R_armor2camera_cv, rvec); + cv::Mat R_armor2camera_cv_mat; + cv::eigen2cv(R_armor2camera_cv, R_armor2camera_cv_mat); + cv::Rodrigues(R_armor2camera_cv_mat, rvec); cv::Vec3d tvec(t_armor2camera_cv[0], t_armor2camera_cv[1], t_armor2camera_cv[2]); std::vector image_points; @@ -84,8 +84,8 @@ class ReprojectionUtil { return image_points; } - double SJTU_cost(const std::vector& cv_refs, - const std::vector& cv_pts, const double& inclined) const { + static double SJTU_cost(const std::vector& cv_refs, + const std::vector& cv_pts, const double& inclined) { std::size_t size = cv_refs.size(); std::vector refs; std::vector pts; diff --git a/src/tongji/solver/solved_armor.hpp b/src/tongji/solver/solved_armor.hpp index 7e6fe34..57cbf82 100644 --- a/src/tongji/solver/solved_armor.hpp +++ b/src/tongji/solver/solved_armor.hpp @@ -3,14 +3,15 @@ #include #include -#include "interfaces/armor_in_camera.hpp" #include "data/time_stamped.hpp" +#include "interfaces/armor_in_camera.hpp" #include "util/index.hpp" namespace world_exe::tongji::solver { class SolvedArmor final : public interfaces::IArmorInCamera { public: - explicit SolvedArmor(const std::vector& armors, data::TimeStamp when_image_come) + explicit SolvedArmor( + const std::vector& armors, data::TimeStamp const& when_image_come) : time_stamp_(when_image_come) { for (const auto& armor : armors) { armors_[util::enumeration::GetIndex(armor.id)].emplace_back(armor); diff --git a/src/tongji/solver/solver.cpp b/src/tongji/solver/solver.cpp index 36ffb49..7d26bc9 100644 --- a/src/tongji/solver/solver.cpp +++ b/src/tongji/solver/solver.cpp @@ -31,8 +31,8 @@ class Solver::Impl { , t_camera2gimbal_(Eigen::Vector3d::Zero()) , reprojection_util_(std::make_unique()) { } - std::shared_ptr EstimateAllArmorPoses( - std::shared_ptr armors_in_image) { + static std::shared_ptr EstimateAllArmorPoses( + std::shared_ptr const& armors_in_image) { std::vector armor_plates; if (!armors_in_image) return nullptr; for (int i = 0; i < static_cast(enumeration::ArmorIdFlag::Count); i++) { @@ -53,7 +53,7 @@ class Solver::Impl { t_camera2gimbal_ = t_camera2gimbal; } - auto Camera2Gimbal(const Eigen::Vector3d& xyz_in_camera) const -> const auto { + auto Camera2Gimbal(const Eigen::Vector3d& xyz_in_camera) const -> auto { Eigen::Vector3d xyz_in_gimbal = R_camera2gimbal_.transpose() * xyz_in_camera + t_camera2gimbal_; return xyz_in_gimbal; @@ -61,7 +61,7 @@ class Solver::Impl { auto CalculateOptimizeYaw(const data::ArmorImageSpacing& armor_in_image, const Eigen::Vector3d& armor_xyz_in_gimbal, const double& gimbal_yaw, - const double& initial_armor_yaw_in_gimbal) const -> const double { + const double& initial_armor_yaw_in_gimbal) const -> double { constexpr double SEARCH_RANGE = 140; // degree const auto yaw0 = util::math::clamp_pm_pi(gimbal_yaw - SEARCH_RANGE / 2 * CV_PI / 180.0); @@ -86,13 +86,13 @@ class Solver::Impl { return best_yaw; } - const data::TimeStamp GetTimeStamp() const { + static data::TimeStamp GetTimeStamp() { return data::TimeStamp(std::chrono::steady_clock::now().time_since_epoch()); } private: - data::ArmorCameraSpacing EstimatePose( - const world_exe::data::ArmorImageSpacing& armor_in_image) const { + static data::ArmorCameraSpacing EstimatePose( + const world_exe::data::ArmorImageSpacing& armor_in_image) { const auto& [xyz_in_camera, R_armor2camera] = EstimatePnp(armor_in_image); data::ArmorCameraSpacing pose; @@ -102,8 +102,8 @@ class Solver::Impl { return pose; } - auto EstimatePnp(const world_exe::data::ArmorImageSpacing& armor_in_image) const - -> const std::tuple { + static auto EstimatePnp(const world_exe::data::ArmorImageSpacing& armor_in_image) + -> std::tuple { const auto& object_points = armor_in_image.isLargeArmor ? parameters::Robomaster::LargeArmorObjectPointsOpencv : parameters::Robomaster::NormalArmorObjectPointsOpencv; @@ -151,12 +151,12 @@ void Solver::SetCamera2Gimbal( auto Solver::CalculateOptimizeYaw(const data::ArmorImageSpacing& armor_in_image, const Eigen::Vector3d& armor_xyz_in_gimbal, const double& gimbal_yaw, - const double& initial_armor_yaw_in_gimbal) const -> const double { + const double& initial_armor_yaw_in_gimbal) const -> double { return pimpl_->CalculateOptimizeYaw( armor_in_image, armor_xyz_in_gimbal, gimbal_yaw, initial_armor_yaw_in_gimbal); } -auto Solver::Camera2Gimbal(const Eigen::Vector3d& xyz_in_camera) const -> const auto { +auto Solver::Camera2Gimbal(const Eigen::Vector3d& xyz_in_camera) const -> auto { return pimpl_->Camera2Gimbal(xyz_in_camera); } } diff --git a/src/tongji/solver/solver.hpp b/src/tongji/solver/solver.hpp index 5247343..3a9ec51 100644 --- a/src/tongji/solver/solver.hpp +++ b/src/tongji/solver/solver.hpp @@ -15,10 +15,10 @@ class Solver final : public interfaces::IPnpSolver { void SetCamera2Gimbal( const Eigen::Matrix3d& R_camera2gimbal, const Eigen::Vector3d& t_camera2gimbal); - auto Camera2Gimbal(const Eigen::Vector3d& xyz_in_camera) const -> const auto; + auto Camera2Gimbal(const Eigen::Vector3d& xyz_in_camera) const -> auto; auto CalculateOptimizeYaw(const data::ArmorImageSpacing& armor_in_image, const Eigen::Vector3d& armor_xyz_in_gimbal, const double& gimbal_yaw, - const double& initial_armor_yaw_in_gimbal) const -> const double; + const double& initial_armor_yaw_in_gimbal) const -> double; Solver(const Solver&) = delete; Solver& operator=(const Solver&) = delete; diff --git a/src/tongji/state_machine/state_machine.cpp b/src/tongji/state_machine/state_machine.cpp index 6400fab..f7075f8 100644 --- a/src/tongji/state_machine/state_machine.cpp +++ b/src/tongji/state_machine/state_machine.cpp @@ -3,6 +3,7 @@ #include #include "../identifier/tracker.hpp" +#include "data/time_stamped.hpp" #include "enum/car_id.hpp" namespace world_exe::tongji::state_machine { @@ -15,13 +16,11 @@ class StateMachine::Impl { const enumeration::CarIDFlag& GetAllowdToFires() const { return target_id_; } - void Update(std::shared_ptr armors_in_image, - const enumeration::CarIDFlag& invincible_armors, - const std::chrono::milliseconds& duration_from_last_update) { - + void Update(std::shared_ptr const& armors_in_image, + const enumeration::CarIDFlag& invincible_armors, data::TimeStamp const& time_stamp) { target_id_ = enumeration::CarIDFlag::None; - target_id_ = tracker_->SelectTrackingTargetID( - armors_in_image, invincible_armors, duration_from_last_update); + target_id_ = + tracker_->SelectTrackingTargetID(armors_in_image, invincible_armors, time_stamp); } void SetLostState() { @@ -42,10 +41,9 @@ const enumeration::CarIDFlag& StateMachine::GetAllowdToFires() const { return pimpl_->GetAllowdToFires(); } -void StateMachine::Update(std::shared_ptr armors_in_image, - const enumeration::CarIDFlag& invincible_armors, - const std::chrono::milliseconds& duration_from_last_update) { - return pimpl_->Update(armors_in_image, invincible_armors, duration_from_last_update); +void StateMachine::Update(std::shared_ptr const& armors_in_image, + const enumeration::CarIDFlag& invincible_armors, data::TimeStamp const& time_stamp) { + return pimpl_->Update(armors_in_image, invincible_armors, time_stamp); } void StateMachine::SetLostState() { return pimpl_->SetLostState(); } diff --git a/src/tongji/state_machine/state_machine.hpp b/src/tongji/state_machine/state_machine.hpp index 82895da..77c92a7 100644 --- a/src/tongji/state_machine/state_machine.hpp +++ b/src/tongji/state_machine/state_machine.hpp @@ -15,9 +15,8 @@ class StateMachine final : public interfaces::ICarState { const enumeration ::CarIDFlag& GetAllowdToFires() const override; - void Update(std::shared_ptr armors_in_image, - const enumeration::CarIDFlag& invincible_armors, - const std::chrono::milliseconds& duration_from_last_update); + void Update(std::shared_ptr const& armors_in_image, + const enumeration::CarIDFlag& invincible_armors, data::TimeStamp const& time_stamp); void SetLostState(); diff --git a/src/util/parameters/params_system_v1.cpp b/src/util/parameters/params_system_v1.cpp index f86d58d..e9b52fa 100644 --- a/src/util/parameters/params_system_v1.cpp +++ b/src/util/parameters/params_system_v1.cpp @@ -1,14 +1,17 @@ #include "parameters/params_system_v1.hpp" +#include #include #include namespace world_exe::parameters { struct ParamsForSystemV1::Impl { public: - std::string model_path = "/workspaces/src/alliance_ros_auto_aim/alliance_auto_aim/models/" - "szu_identify_model.onnx"; - std::string device = "AUTO"; + std::string model_path = + std::filesystem::path { __FILE__ }.parent_path().parent_path().parent_path().parent_path() + / "models" / "szu_identify_model.onnx"; + + std::string device = "AUTO"; double control_delay_in_second = 0.05; double velocity_begin = 26; double gravity = 9.81; diff --git a/src/v1/auto_aim_system_v1.cpp b/src/v1/auto_aim_system_v1.cpp index bdb36be..99c2793 100644 --- a/src/v1/auto_aim_system_v1.cpp +++ b/src/v1/auto_aim_system_v1.cpp @@ -35,7 +35,7 @@ using namespace std::chrono; class world_exe::v1::SystemV1::Impl{ public: - Impl(const bool& debug) : debug(debug) { + explicit Impl(const bool& debug) : debug(debug) { time_point_ = std::chrono::steady_clock::now(); predictor = std::make_shared(); sync = std::make_shared(seconds(2),6e-6); diff --git a/src/v1/fire_controller/fire_controller.cpp b/src/v1/fire_controller/fire_controller.cpp index de57210..02d4849 100644 --- a/src/v1/fire_controller/fire_controller.cpp +++ b/src/v1/fire_controller/fire_controller.cpp @@ -15,7 +15,7 @@ class world_exe::v1::fire_control::TracingFireControl::Impl { : control_delay_((static_cast(control_delay_in_second * 1e9))) , velocity_begin_(velocity_begin) , gravity_(gravity) { } - const enumeration::CarIDFlag GetAttackCarId() const { + enumeration::CarIDFlag GetAttackCarId() const { double max_dot = -2; enumeration::CarIDFlag ret = enumeration::ArmorIdFlag::None; @@ -46,9 +46,9 @@ class world_exe::v1::fire_control::TracingFireControl::Impl { predictor_ = predictor; }; - const world_exe::data::FireControl CalculateTarget(const std::chrono::seconds& time_duration) { - std::chrono::seconds fly_time{0}; - const auto& pre1 = predictor_->Predictor(fly_time + time_duration + control_delay_); + world_exe::data::FireControl CalculateTarget(data::TimeStamp const& time_stamp) { + std::chrono::seconds fly_time { 0 }; + const auto& pre1 = predictor_->Predictor(time_stamp + fly_time + control_delay_); const auto& pre2 = pre1->GetArmors(predictor_->GetId()); double min_angular_dis = 1e9; int index = -1, index_ = 0; @@ -66,14 +66,14 @@ class world_exe::v1::fire_control::TracingFireControl::Impl { if (index == -1) return no_allow_; for (int i = 5; i-- > 0;) { - const auto& armors_in_gimbal_control = - predictor_->Predictor(fly_time + time_duration + control_delay_); + const auto& armors_in_gimbal_control = predictor_->Predictor(fly_time + control_delay_); const auto& armors = armors_in_gimbal_control->GetArmors(predictor_->GetId()); const auto& [fly_time, dir] = trajectory_solver::gravity_only(armors[index].position, velocity_begin_, gravity_); } - return { .time_stamp = data::TimeStamp{std::chrono::nanoseconds(fly_time + time_duration + control_delay_)}, .fire_allowance = true }; + return { .time_stamp = data::TimeStamp { time_stamp + fly_time + control_delay_ }, + .fire_allowance = true }; } private: @@ -87,13 +87,13 @@ class world_exe::v1::fire_control::TracingFireControl::Impl { std::shared_ptr predictor_; }; -const world_exe::data::FireControl // +world_exe::data::FireControl // world_exe::v1::fire_control::TracingFireControl::CalculateTarget( - const std::chrono::seconds& time_duration) const { - return pimpl_->CalculateTarget(time_duration); + data::TimeStamp const& time_stamp) const { + return pimpl_->CalculateTarget(time_stamp); } -const world_exe::enumeration::CarIDFlag +world_exe::enumeration::CarIDFlag world_exe::v1::fire_control::TracingFireControl::GetAttackCarId() const { return pimpl_->GetAttackCarId(); } diff --git a/src/v1/fire_controller/fire_controller.hpp b/src/v1/fire_controller/fire_controller.hpp index 171c0e6..1b753fe 100644 --- a/src/v1/fire_controller/fire_controller.hpp +++ b/src/v1/fire_controller/fire_controller.hpp @@ -1,15 +1,15 @@ #pragma once #include "data/fire_control.hpp" +#include "data/time_stamped.hpp" #include "interfaces/fire_controller.hpp" #include "interfaces/predictor.hpp" -#include #include namespace world_exe::v1::fire_control { class TracingFireControl final : public interfaces::IFireControl { public: - const data::FireControl CalculateTarget(const std::chrono::seconds& time_duration) const override; - const enumeration::CarIDFlag GetAttackCarId() const override; + data::FireControl CalculateTarget(data::TimeStamp const& time_stamp) const override; + enumeration::CarIDFlag GetAttackCarId() const override; void set_armor(const std::shared_ptr& armors); void SetPredictor(const std::shared_ptr& predictor); void SetTargetCarID(const enumeration::CarIDFlag& tracing_id); diff --git a/src/v1/predictor/car/car_predictor.cpp b/src/v1/predictor/car/car_predictor.cpp index 43c674f..b087fd7 100644 --- a/src/v1/predictor/car/car_predictor.cpp +++ b/src/v1/predictor/car/car_predictor.cpp @@ -15,10 +15,11 @@ class CarPredictor::Impl { const enumeration::ArmorIdFlag& GetId() const { return id_; } - std::shared_ptr Predictor(const data::TimeStamp& time_stamp) { + std::shared_ptr Predictor( + const data::TimeStamp& time_stamp) { auto ptr = std::make_shared(); - ptr->SetWithSingleId(ekf_.get_predict_output_armor( - id_, (time_stamp - create_time_stamp_).to_seconds()), + ptr->SetWithSingleId( + ekf_.get_predict_output_armor(id_, (time_stamp - create_time_stamp_).to_seconds()), time_stamp); return ptr; } @@ -27,9 +28,9 @@ class CarPredictor::Impl { inline void SetEkf(const CarPredictEkf& ekf) { ekf_ = ekf; } - inline void SetTimeStamp(const data::TimeStamp& time_stamp) { - create_time_stamp_ = time_stamp; - } + inline void SetTimeStamp(const data::TimeStamp& time_stamp) { create_time_stamp_ = time_stamp; } + + data ::TimeStamp GetTimeStamp() const { return create_time_stamp_; } private: enumeration::CarIDFlag id_; @@ -39,7 +40,7 @@ class CarPredictor::Impl { CarPredictor::CarPredictor() : pimpl_(std::make_unique( - enumeration::CarIDFlag::None, CarPredictEkf {}, data::TimeStamp {})) { } + enumeration::CarIDFlag::None, CarPredictEkf { }, data::TimeStamp { })) { } CarPredictor::CarPredictor(const enumeration::CarIDFlag& id, const CarPredictEkf& ekf, const data::TimeStamp& create_time_stamp) @@ -61,4 +62,5 @@ void CarPredictor::SetEkf(const CarPredictEkf& ekf) { return pimpl_->SetEkf(ekf) void CarPredictor::SetTimeStamp(const data::TimeStamp& time_stamp) { return pimpl_->SetTimeStamp(time_stamp); }; + } \ No newline at end of file diff --git a/src/v1/predictor/car/car_predictor.hpp b/src/v1/predictor/car/car_predictor.hpp index 9289164..e9776a1 100644 --- a/src/v1/predictor/car/car_predictor.hpp +++ b/src/v1/predictor/car/car_predictor.hpp @@ -6,7 +6,7 @@ #include "interfaces/predictor.hpp" namespace world_exe::v1::predictor { -class CarPredictor final: public interfaces::IPredictor { +class CarPredictor final : public interfaces::IPredictor { public: CarPredictor(); ~CarPredictor(); diff --git a/src/v1/predictor/predictor_manager.cpp b/src/v1/predictor/predictor_manager.cpp index f4f2b65..a0614b5 100644 --- a/src/v1/predictor/predictor_manager.cpp +++ b/src/v1/predictor/predictor_manager.cpp @@ -31,7 +31,7 @@ class PredictorManager::Impl { std::atan(tmp_armor.position.y() / tmp_armor.position.x()), -std::atan(tmp_armor.position.z() / tmp_armor.position.x()), tmp_armor.position.norm(); - predictors_[i].Update(input, {}, dt.to_seconds()); + predictors_[i].Update(input, { }, dt.to_seconds()); } else if (armors.size() == 2) { // 当同时识别到两块装甲板时,优先更新近的那块,再更新远的 const auto armor0_yaw = util::math::get_yaw_from_quaternion(armors[0].orientation); @@ -47,27 +47,27 @@ class PredictorManager::Impl { std::atan(tmp_armor0.position.y() / tmp_armor0.position.x()), -std::atan(tmp_armor0.position.z() / tmp_armor0.position.x()), tmp_armor0.position.norm(); - predictors_[i].Update(input, {}, dt.to_seconds()); + predictors_[i].Update(input, { }, dt.to_seconds()); // 同时识别到一辆车的两块装甲板时要调这个函数 predictors_[i].set_second_armor(); input << util::math::get_yaw_from_quaternion(tmp_armor1.orientation), std::atan(tmp_armor1.position.y() / tmp_armor1.position.x()), -std::atan(tmp_armor1.position.z() / tmp_armor1.position.x()), tmp_armor1.position.norm(); - predictors_[i].Update(input, {}, 0.); + predictors_[i].Update(input, { }, 0.); } else { input << util::math::get_yaw_from_quaternion(tmp_armor1.orientation), std::atan(tmp_armor1.position.y() / tmp_armor1.position.x()), -std::atan(tmp_armor1.position.z() / tmp_armor1.position.x()), tmp_armor1.position.norm(); - predictors_[i].Update(input, {}, dt.to_seconds()); + predictors_[i].Update(input, { }, dt.to_seconds()); // 同时识别到一辆车的两块装甲板时要调这个函数 predictors_[i].set_second_armor(); input << util::math::get_yaw_from_quaternion(tmp_armor0.orientation), std::atan(tmp_armor0.position.y() / tmp_armor0.position.x()), -std::atan(tmp_armor0.position.z() / tmp_armor0.position.x()), tmp_armor0.position.norm(); - predictors_[i].Update(input, {}, 0.); + predictors_[i].Update(input, { }, 0.); } } } @@ -99,7 +99,7 @@ class PredictorManager::Impl { } private: - data::TimeStamp last_update_time_stamp_ {}; + data::TimeStamp last_update_time_stamp_ { }; std::array predictors_; Eigen::Affine3d transform_from_camera_to_gimbal_; @@ -116,7 +116,7 @@ std::shared_ptr PredictorManager::Predict( return pimpl_->Predict(id, time_stamp); }; -void PredictorManager::Update(std::shared_ptr data) { +void PredictorManager::Update(std::shared_ptrdata) { return pimpl_->Update(data); };