diff --git a/src/cxx/component.cc b/src/cxx/component.cc index 415bf24..9b64dc0 100644 --- a/src/cxx/component.cc +++ b/src/cxx/component.cc @@ -1,3 +1,4 @@ +#include #if defined(__clang__) # pragma clang diagnostic ignored "-Wdeprecated-declarations" #elif defined(__GNUC__) @@ -7,7 +8,9 @@ #include "cxx/context.hh" #include "cxx/util/navigation/navigation.hh" #include "cxx/util/node_mixin.hh" - +#include +#include +#include #include #include @@ -52,6 +55,12 @@ class Navigation OutputInterface chassis_behavior; OutputInterface chassis_speed; OutputInterface gimbal_speed; + OutputInterface sentry_decision_enabled; + OutputInterface sentry_bullet_exchange_value; + OutputInterface requested_mode; + OutputInterface sentry_confirm_revive; + std::chrono::steady_clock::time_point sentry_decision_clear_at = + std::chrono::steady_clock::time_point::min(); auto init(Navigation& component) -> void { component.register_output("/rmcs_navigation/enable_control", enable_control, false); @@ -62,6 +71,71 @@ class Navigation "/rmcs_navigation/chassis_velocity", chassis_speed, Eigen::Vector2d::Zero()); component.register_output( "/rmcs_navigation/gimbal_velocity", gimbal_speed, Eigen::Vector2d::Zero()); + component.register_output( + "/referee/sentry/decision/enabled", sentry_decision_enabled, false); + component.register_output( + "/referee/sentry/decision/bullet_exchange_value", sentry_bullet_exchange_value, + std::uint16_t{0}); + component.register_output( + "/referee/sentry/decision/mode", requested_mode, std::uint8_t{0}); + component.register_output( + "/referee/sentry/decision/confirm_revive", sentry_confirm_revive, false); + } + + auto exchange_17mm_bullet(int amount) -> void { + constexpr int max_bullet_exchange_value = 0x07ff; + amount = std::clamp(amount, 0, max_bullet_exchange_value); + + if (amount == 0) { + clear_sentry_decision(); + return; + } + + reset_all_decisions(); + *sentry_bullet_exchange_value = static_cast(amount); + activate_decision(); + } + + auto switch_mode(int mode) -> void { + if (mode < 1 || mode > 3) + return; + + reset_all_decisions(); + *requested_mode = static_cast(mode); + activate_decision(); + } + + auto confirm_revive() -> void { + reset_all_decisions(); + *sentry_confirm_revive = true; + activate_decision(); + } + + auto update() -> void { + if (sentry_decision_clear_at == std::chrono::steady_clock::time_point::min()) + return; + + if (std::chrono::steady_clock::now() >= sentry_decision_clear_at) + clear_sentry_decision(); + } + + private: + auto reset_all_decisions() -> void { + *sentry_bullet_exchange_value = std::uint16_t{0}; + *requested_mode = std::uint8_t{0}; + *sentry_confirm_revive = false; + } + + auto activate_decision() -> void { + *sentry_decision_enabled = true; + sentry_decision_clear_at = + std::chrono::steady_clock::now() + std::chrono::milliseconds{800}; + } + + auto clear_sentry_decision() -> void { + *sentry_decision_enabled = false; + reset_all_decisions(); + sentry_decision_clear_at = std::chrono::steady_clock::time_point::min(); } } command; @@ -108,6 +182,15 @@ class Navigation api.set_function("update_chassis_vel", [this](double x, double y) { *command.chassis_speed = Eigen::Vector2d{x, y}; }); + api.set_function("exchange_17mm_bullet", [this](int amount) { + command.exchange_17mm_bullet(amount); + }); + api.set_function("switch_mode", [this](int mode) { + command.switch_mode(mode); + }); + api.set_function("confirm_revive", [this]()-> void { + command.confirm_revive(); + }); } auto make_option_injection() { @@ -156,20 +239,112 @@ class Navigation auto lua_sync() { const auto [x, y, yaw] = navigation.check_position(); + auto read_context = + [](const details::Context::InputInterface& input, T fallback) -> T { + if (input.ready()) + return *input; + + return fallback; + }; + auto user = lua_blackboard["user"].get(); - user["health"] = *context.robot_health; - user["bullet"] = *context.robot_bullet; - user["chassis_power_limit"] = *context.chassis_power_limit_referee; + user["health"] = read_context(context.robot_health, std::uint16_t{0}); + user["bullet"] = read_context(context.robot_bullet, std::uint16_t{0}); + user["chassis_power_limit"] = read_context(context.chassis_power_limit_referee, 0.0); user["x"] = x; user["y"] = y; user["yaw"] = yaw; + user["chassis_power"] = read_context(context.chassis_power_referee, 0.0); + user["chassis_buffer_energy"] = read_context(context.chassis_buffer_energy_referee, 0.0); + user["chassis_output_status"] = read_context(context.chassis_output_status, false); + user["shooter_cooling"] = read_context(context.robot_shooter_cooling, std::int64_t{0}); + user["shooter_heat_limit"] = + read_context(context.robot_shooter_heat_limit, std::int64_t{0}); + user["bullet_42mm"] = read_context(context.robot_42mm_bullet, std::uint16_t{0}); + user["fortress_17mm_bullet"] = + read_context(context.robot_fortress_17mm_bullet, std::uint16_t{0}); + user["initial_speed"] = read_context(context.robot_initial_speed, 0.0F); + user["shoot_timestamp"] = read_context(context.robot_shoot_timestamp, 0.0); auto game = lua_blackboard["game"].get(); - game["stage"] = rmcs_msgs::to_string(*context.game_stage); + game["stage"] = + rmcs_msgs::to_string(read_context(context.game_stage, rmcs_msgs::GameStage::UNKNOWN)); + game["sync_timestamp"] = read_context(context.sync_timestamp, std::uint64_t{0}); + game["outpost_health"] = read_context(context.ally_outpost_hp, std::uint16_t{0}); + game["base_health"] = read_context(context.ally_base_hp, std::uint16_t{0}); + game["hero_health"] = read_context(context.ally_hero_hp, std::uint16_t{0}); + game["infantry_1_health"] = read_context(context.ally_infantry_1_hp, std::uint16_t{0}); + game["infantry_2_health"] = read_context(context.ally_infantry_2_hp, std::uint16_t{0}); + game["engineer_health"] = read_context(context.ally_engineer_hp, std::uint16_t{0}); + game["remaining_time"] = read_context(context.stage_remain_time, std::uint16_t{0}); + game["gold_coin"] = read_context(context.remaining_gold_coin, std::uint16_t{0}); + game["exchangeable_ammunition_quantity"] = + read_context(context.sentry_exchangeable_bullet, std::uint16_t{0}); + const auto our_dart_number_of_hits = static_cast( + read_context(context.dart_latest_hit_target_total_count, std::uint8_t{0})); + game["our_dart_number_of_hits"] = our_dart_number_of_hits; + game["fortress_occupied"] = + read_context(context.ally_fortress_occupation_status, std::uint8_t{0}) != 0; + game["big_energy_mechanism_activated"] = + read_context(context.ally_big_energy_activation_status, std::uint8_t{0}) != 0; + game["small_energy_mechanism_activated"] = + read_context(context.ally_small_energy_activation_status, std::uint8_t{0}) != 0; + game["red_score"] = read_context(context.red_score, std::uint32_t{0}); + game["blue_score"] = read_context(context.blue_score, std::uint32_t{0}); + + auto set_position = [](sol::table position, double x, double y) { + position["x"] = x; + position["y"] = y; + }; + set_position( + game["hero_position"].get(), + read_context(context.ally_hero_position_x, 0.0), + read_context(context.ally_hero_position_y, 0.0)); + set_position( + game["infantry_1_position"].get(), + read_context(context.ally_infantry_1_position_x, 0.0), + read_context(context.ally_infantry_1_position_y, 0.0)); + set_position( + game["infantry_2_position"].get(), + read_context(context.ally_infantry_2_position_x, 0.0), + read_context(context.ally_infantry_2_position_y, 0.0)); + set_position( + game["engineer_position"].get(), + read_context(context.ally_engineer_position_x, 0.0), + read_context(context.ally_engineer_position_y, 0.0)); + + game["robot_id"] = static_cast( + read_context(context.robot_id, rmcs_msgs::RobotId{rmcs_msgs::RobotId::UNKNOWN})); + game["can_confirm_free_revive"] = + read_context(context.sentry_can_confirm_free_revive, false); + game["can_exchange_instant_revive"] = + read_context(context.sentry_can_exchange_instant_revive, false); + game["instant_revive_cost"] = + read_context(context.sentry_instant_revive_cost, std::uint16_t{0}); + game["exchanged_bullet"] = + read_context(context.sentry_exchanged_bullet, std::uint16_t{0}); + game["remote_bullet_exchange_count"] = + read_context(context.sentry_remote_bullet_exchange_count, std::uint8_t{0}); + game["sentry_mode"] = read_context(context.sentry_mode, std::uint8_t{0}); + game["energy_mechanism_activatable"] = + read_context(context.sentry_energy_mechanism_activatable, false); auto play = lua_blackboard["play"].get(); - play["rswitch"] = rmcs_msgs::to_string(*context.switch_right); - play["lswitch"] = rmcs_msgs::to_string(*context.switch_left); + play["rswitch"] = + rmcs_msgs::to_string(read_context(context.switch_right, rmcs_msgs::Switch::UNKNOWN)); + play["lswitch"] = + rmcs_msgs::to_string(read_context(context.switch_left, rmcs_msgs::Switch::UNKNOWN)); + auto map_command = lua_blackboard["map_command"].get(); + map_command["x"] = read_context(context.map_command_event_x, 0.0); + map_command["y"] = read_context(context.map_command_event_y, 0.0); + map_command["keyboard"] = + static_cast(read_context(context.map_command_event_keyboard, std::uint8_t{0})); + map_command["target_robot_id"] = static_cast( + read_context(context.map_command_event_target_robot_id, std::uint8_t{0})); + map_command["source"] = + static_cast(read_context(context.map_command_event_source, std::uint16_t{0})); + map_command["sequence"] = + read_context(context.map_command_event_sequence, std::uint64_t{0}); auto meta = lua_blackboard["meta"].get(); meta["timestamp"] = this->now().seconds(); @@ -266,6 +441,11 @@ class Navigation } auto update() -> void override { + { + auto lock = std::scoped_lock{io_mutex}; + command.update(); + } + if (lua_tick_count++ == 100) { lua_tick_count = 0; auto lock = std::scoped_lock{io_mutex}; diff --git a/src/cxx/context.cc b/src/cxx/context.cc index 25cbf8d..8fed00a 100644 --- a/src/cxx/context.cc +++ b/src/cxx/context.cc @@ -85,13 +85,94 @@ struct Context::Impl { auto init(std::mutex& io_mutex, bool mock) { make_input("/referee/chassis/power_limit", context.chassis_power_limit_referee, mock); + make_input("/referee/chassis/power", context.chassis_power_referee, mock); + make_input("/referee/chassis/buffer_energy", context.chassis_buffer_energy_referee, mock); + make_input("/referee/chassis/output_status", context.chassis_output_status, mock); make_input("/referee/id", context.robot_id, mock); make_input("/remote/switch/right", context.switch_right, mock); make_input("/remote/switch/left", context.switch_left, mock); make_input("/referee/game/stage", context.game_stage, mock); + make_input("/referee/game/stage_remain_time", context.stage_remain_time, mock); + make_input("/referee/game/sync_timestamp", context.sync_timestamp, mock); + make_input( + "/referee/event/ally_big_energy_activation_status", + context.ally_big_energy_activation_status, mock); + make_input( + "/referee/event/ally_small_energy_activation_status", + context.ally_small_energy_activation_status, mock); + make_input( + "/referee/event/ally_fortress_occupation_status", + context.ally_fortress_occupation_status, mock); + make_input( + "/referee/dart/latest_hit_target_total_count", + context.dart_latest_hit_target_total_count, mock); make_input("/referee/current_hp", context.robot_health, mock); make_input("/referee/shooter/bullet_allowance", context.robot_bullet, mock); + make_input("/referee/shooter/cooling", context.robot_shooter_cooling, mock); + make_input("/referee/shooter/heat_limit", context.robot_shooter_heat_limit, mock); + make_input("/referee/shooter/42mm_bullet_allowance", context.robot_42mm_bullet, mock); + make_input( + "/referee/shooter/fortress_17mm_bullet_allowance", + context.robot_fortress_17mm_bullet, mock); + make_input("/referee/remaining_gold_coin", context.remaining_gold_coin, mock); + make_input("/referee/shooter/initial_speed", context.robot_initial_speed, mock); + make_input("/referee/shooter/shoot_timestamp", context.robot_shoot_timestamp, mock); + make_input( + "/referee/map_command/event/target_position_x", context.map_command_event_x, mock); + make_input( + "/referee/map_command/event/target_position_y", context.map_command_event_y, mock); + make_input( + "/referee/map_command/event/keyboard", context.map_command_event_keyboard, mock); + make_input( + "/referee/map_command/event/target_robot_id", + context.map_command_event_target_robot_id, mock); + make_input("/referee/map_command/event/source", context.map_command_event_source, mock); + make_input( + "/referee/map_command/event/sequence", context.map_command_event_sequence, mock); + + make_input("/referee/ally/hero_hp", context.ally_hero_hp, mock); + make_input("/referee/ally/engineer_hp", context.ally_engineer_hp, mock); + make_input("/referee/ally/infantry_1_hp", context.ally_infantry_1_hp, mock); + make_input("/referee/ally/infantry_2_hp", context.ally_infantry_2_hp, mock); + make_input("/referee/ally/outpost/hp", context.ally_outpost_hp, mock); + make_input("/referee/ally/base/hp", context.ally_base_hp, mock); + make_input("/referee/ally/hero_position_x", context.ally_hero_position_x, mock); + make_input("/referee/ally/hero_position_y", context.ally_hero_position_y, mock); + make_input("/referee/ally/engineer_position_x", context.ally_engineer_position_x, mock); + make_input("/referee/ally/engineer_position_y", context.ally_engineer_position_y, mock); + make_input( + "/referee/ally/infantry_1_position_x", context.ally_infantry_1_position_x, mock); + make_input( + "/referee/ally/infantry_1_position_y", context.ally_infantry_1_position_y, mock); + make_input( + "/referee/ally/infantry_2_position_x", context.ally_infantry_2_position_x, mock); + make_input( + "/referee/ally/infantry_2_position_y", context.ally_infantry_2_position_y, mock); + + make_input( + "/referee/sentry/can_confirm_free_revive", + context.sentry_can_confirm_free_revive, mock); + make_input( + "/referee/sentry/can_exchange_instant_revive", + context.sentry_can_exchange_instant_revive, mock); + make_input( + "/referee/sentry/instant_revive_cost", context.sentry_instant_revive_cost, mock); + make_input( + "/referee/sentry/exchanged_bullet_allowance", + context.sentry_exchanged_bullet, mock); + make_input( + "/referee/sentry/remote_bullet_exchange_count", + context.sentry_remote_bullet_exchange_count, mock); + make_input( + "/referee/sentry/exchangeable_bullet_allowance", + context.sentry_exchangeable_bullet, mock); + make_input("/referee/sentry/mode", context.sentry_mode, mock); + make_input( + "/referee/sentry/energy_mechanism_activatable", + context.sentry_energy_mechanism_activatable, mock); + make_input("/referee/game/red_score", context.red_score, mock); + make_input("/referee/game/blue_score", context.blue_score, mock); if (mock) { constexpr auto topic = "/rmcs_navigation/context/mock"; diff --git a/src/cxx/context.hh b/src/cxx/context.hh index ee89659..62a3ef7 100644 --- a/src/cxx/context.hh +++ b/src/cxx/context.hh @@ -1,6 +1,7 @@ #pragma once #include "util/pimpl.hh" +#include #include #include #include @@ -21,14 +22,58 @@ public: using InputInterface = rmcs_executor::Component::InputInterface; InputInterface game_stage; + InputInterface stage_remain_time; + InputInterface sync_timestamp; + InputInterface ally_big_energy_activation_status; + InputInterface ally_small_energy_activation_status; + InputInterface ally_fortress_occupation_status; + InputInterface dart_latest_hit_target_total_count; InputInterface robot_id; + InputInterface robot_shooter_cooling; + InputInterface robot_shooter_heat_limit; + InputInterface chassis_power_limit_referee; + InputInterface chassis_power_referee; + InputInterface chassis_buffer_energy_referee; + InputInterface chassis_output_status; + InputInterface ally_hero_hp; + InputInterface ally_engineer_hp; + InputInterface ally_infantry_1_hp; + InputInterface ally_infantry_2_hp; + InputInterface ally_outpost_hp; + InputInterface ally_base_hp; + InputInterface ally_hero_position_x; + InputInterface ally_hero_position_y; + InputInterface ally_engineer_position_x; + InputInterface ally_engineer_position_y; + InputInterface ally_infantry_1_position_x; + InputInterface ally_infantry_1_position_y; + InputInterface ally_infantry_2_position_x; + InputInterface ally_infantry_2_position_y; InputInterface robot_health; InputInterface robot_bullet; + InputInterface robot_42mm_bullet; + InputInterface robot_fortress_17mm_bullet; + InputInterface remaining_gold_coin; + InputInterface robot_initial_speed; + InputInterface robot_shoot_timestamp; + InputInterface map_command_event_x; + InputInterface map_command_event_y; + InputInterface map_command_event_keyboard; + InputInterface map_command_event_target_robot_id; + InputInterface map_command_event_source; + InputInterface map_command_event_sequence; + InputInterface sentry_can_confirm_free_revive; + InputInterface sentry_can_exchange_instant_revive; + InputInterface sentry_instant_revive_cost; + InputInterface sentry_exchanged_bullet; + InputInterface sentry_remote_bullet_exchange_count; + InputInterface sentry_exchangeable_bullet; + InputInterface sentry_mode; + InputInterface sentry_energy_mechanism_activatable; InputInterface red_score; InputInterface blue_score; InputInterface switch_right; InputInterface switch_left; - InputInterface chassis_power_limit_referee; explicit Context(rclcpp::Node& node, rmcs_executor::Component& component) noexcept; diff --git a/src/lua/action.lua b/src/lua/action.lua index e9193b6..ae7d515 100644 --- a/src/lua/action.lua +++ b/src/lua/action.lua @@ -77,6 +77,21 @@ function action:update_chassis_vel(x, y) api.update_chassis_vel(x, y) end +-- 注意exchange_17mm_bullet switch_mode confirm_revive 不能同时进行,保护策略(详见component.cc)会清空同时发出的其他命令 +function action:exchange_17mm_bullet(amount) + amount = blackboard.game.exchanged_bullet + amount + api.exchange_17mm_bullet(amount) +end + +function action:switch_mode(mode) + api.switch_mode(mode) +end + +-- 配合can_confirm_free_revive使用 +function action:confirm_revive() + api.confirm_revive() +end + function action:restart_navigation(config) return api.restart_navigation(config) end diff --git a/src/lua/api.lua b/src/lua/api.lua index e7cef9e..3caf0d3 100644 --- a/src/lua/api.lua +++ b/src/lua/api.lua @@ -13,10 +13,13 @@ local util = require("util.native") --- @field fuck fun(message: string) --- --- @field send_target fun(x: number, y: number) ---- @field update_gimbal_direction fun(angle: number) +--- @field update_gimbal_direction fun(angle: number) --- @field update_gimbal_dominator fun(name: string) --- @field update_chassis_mode fun(mode: string) --- @field update_chassis_vel fun(x: number, y: number) +--- @field exchange_17mm_bullet fun(amount: integer) +--- @field switch_mode fun(mode: number) +--- @field confirm_revive fun() --- local api = setmetatable({}, { __index = function(_, name) @@ -58,17 +61,18 @@ function api.restart_navigation(config) -- FIXME: 存在调试用的进程(foxglove),记得去掉 local command = [[ - source %q +source %q - screen -S rmcs-navigation -X quit +screen -S rmcs-navigation -X quit - screen -dmS rmcs-navigation - screen -S rmcs-navigation -X screen bash -lc "ros2 launch foxglove_bridge foxglove_bridge_launch.xml" +screen -dmS rmcs-navigation +screen -S rmcs-navigation -X screen bash -lc "ros2 launch foxglove_bridge foxglove_bridge_launch.xml" - configs=%q - screen -S rmcs-navigation -X screen bash -lc "ros2 launch rmcs-navigation motion.launch.yaml $configs" - screen -S rmcs-navigation -X screen bash -lc "ros2 launch rmcs-navigation sensor.launch.yaml $configs" - ]] +configs=%q +screen -S rmcs-navigation -X screen bash -lc "ros2 launch rmcs-navigation sensor.launch.yaml $configs" +sleep 1 +screen -S rmcs-navigation -X screen bash -lc "ros2 launch rmcs-navigation motion.launch.yaml $configs" +]] local packed_command = string.format(command, filename, configs) return util.run(string.format("(%s) >/dev/null 2>&1 &", packed_command)) diff --git a/src/lua/blackboard.lua b/src/lua/blackboard.lua index dea3bcb..439701b 100644 --- a/src/lua/blackboard.lua +++ b/src/lua/blackboard.lua @@ -6,18 +6,69 @@ local function PointPair(points) end local function create_default_blackboard() + local last_our_dart_number_of_hits = nil local result = { -- Dynamic Information user = { health = 0, bullet = 0, chassis_power_limit = 0, + chassis_power = 0, + chassis_buffer_energy = 0, + chassis_output_status = false, + shooter_cooling = 0, + shooter_heat_limit = 0, + bullet_42mm = 0, + fortress_17mm_bullet = 0, + initial_speed = 0, + shoot_timestamp = 0, x = 0, y = 0, yaw = 0, }, game = { stage = "UNKNOWN", + sync_timestamp = 0, + + outpost_health = 0, -- 前哨站血量 + base_health = 0, -- 基地血量 + + hero_health = 0, + infantry_1_health = 0, + infantry_2_health = 0, + engineer_health = 0, + + hero_position = { x = 0.0, y = 0.0 }, + infantry_1_position = { x = 0.0, y = 0.0 }, + infantry_2_position = { x = 0.0, y = 0.0 }, + engineer_position = { x = 0.0, y = 0.0 }, + + remaining_time = 0, -- 比赛剩余时间 + gold_coin = 0, -- 队伍剩余金币数 + exchangeable_ammunition_quantity = 0, -- 队伍 17mm 允许发弹量的剩余可兑换数 + + our_dart_number_of_hits = 0, -- 己方飞镖击中次数 + fortress_occupied = false, -- 己方堡垒是否被占领 + big_energy_mechanism_activated = false, -- 大能量机关是否被激活 + small_energy_mechanism_activated = false, -- 小能量机关是否被激活 + red_score = 0, + blue_score = 0, + robot_id = 0, + can_confirm_free_revive = false, -- 是否可以确认免费复活(读条结束时可确认) + can_exchange_instant_revive = false, + instant_revive_cost = 0, + exchanged_bullet = 0, + remote_bullet_exchange_count = 0, + sentry_mode = 0, -- 1为进攻姿态 2为防御姿态 3为移动姿态 + energy_mechanism_activatable = false, + }, + map_command = { + x = 0, + y = 0, + keyboard = 0, + target_robot_id = 0, + source = 0, + sequence = 0, }, play = { rswitch = "UNKNOWN", @@ -25,39 +76,75 @@ local function create_default_blackboard() }, meta = { timestamp = 0, -- 秒 + fsm_state = "unknown", + fsm_return_stage = "before_fluctuant", }, -- Static Information rule = { decision = "auxiliary", - -- 状态类规则 + -- 自身状态类规则 + + health_limit = 210, + health_ready = 400, + bullet_limit = 40, + bullet_ready = 160, + + -- 其他状态类规则 + + -- 比赛相关 + time_of_the_competition_red_line = 90, --比赛剩余时间红线 + + -- 队伍资源相关 + exchangeable_ammunition_quantity_red_line = 1000, -- 队伍 17mm 允许发弹量的剩余可兑换数红线 + gold_coin_red_line = 400, -- 队伍剩余金币数红线 - health_limit = 0, - health_ready = 0, - bullet_limit = 0, - bullet_ready = 0, + -- 前哨站相关 + outpost_health_red_line = 1500, + + -- 基地相关 + base_health_red_line = 2000, + + -- 友方机器人相关 + hero_health_ready_red_line = 50, + infantry_1_health_ready_red_line = 50, + infantry_2_health_ready_red_line = 50, + engineer_health_ready_red_line = 50, -- 坐标类规则 -- 定义顺序:ours = 0,them = 1 -- 普通地形坐标 - fortress = PointPair { { 0, 0 }, { 0, 0 } }, -- 堡垒 - resupply_zone = PointPair { { 0, 0 }, { 0, 0 } }, -- 补给点 - road_zone_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路区 + fortress = PointPair { { 0, 0 }, { 0, 0 } }, -- 堡垒 + resupply_zone = PointPair { { 0, 0 }, { 0, 0 } }, -- 补给点 + road_zone_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路区 road_zone_final = PointPair { { 0, 0 }, { 0, 0 } }, - launch_ramp_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 飞坡 + road_zone_way_point_1 = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路区路径点1 + road_zone_way_point_2 = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路区路径点2 + road_zone_way_point_3 = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路区路径点3 + launch_ramp_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 飞坡 launch_ramp_final = PointPair { { 0, 0 }, { 0, 0 } }, - outpost_resupply = PointPair { { 0, 0 }, { 0, 0 } }, -- 前哨站补给点 + outpost_resupply = PointPair { { 0, 0 }, { 0, 0 } }, -- 前哨站补给点 + attack_outpost_point = PointPair { { 0, 0 }, { 0, 0 } }, -- 攻击前哨站点 assembly_zone = PointPair { { 0, 0 }, { 0, 0 } }, + central_highland_near_fluctuant_road = PointPair { { 0, 0 }, { 0, 0 } }, -- 中央高地靠近起伏路一侧 + central_highland_near_doghole = PointPair { { 0, 0 }, { 0, 0 } }, -- 中央高地靠近狗洞一侧 + central_highland_middle = PointPair { { 0, 0 }, { 0, 0 } }, -- 中央高地一侧中间 + central_highland_gain_point = PointPair { { 0, 0 }, { 0, 0 } }, -- 中央高地增益点 + central_highland_near_two_steps_and_outpost = PointPair { { 0, 0 }, { 0, 0 } }, -- 中央高地靠近二级台阶(二级台阶增益点和前哨站中间) + base_left_gain_point = PointPair { { 0, 0 }, { 0, 0 } }, -- 左侧基地增益点 + base_right_gain_point = PointPair { { 0, 0 }, { 0, 0 } }, -- 右侧基地增益点 -- 特殊跨越地形坐标 - road_tunnel_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路隧道 + road_tunnel_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路隧道 road_tunnel_final = PointPair { { 0, 0 }, { 0, 0 } }, - one_step_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 一级台阶 - one_step_final = PointPair { { 0, 0 }, { 0, 0 } }, - two_step_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 二级台阶 + one_step_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 一级台阶高点 + one_step_final = PointPair { { 0, 0 }, { 0, 0 } }, -- 一级台阶低点 + two_step_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 二级台阶高点 two_step_final = PointPair { { 0, 0 }, { 0, 0 } }, + fluctuant_road_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 起伏路段 + fluctuant_road_final = PointPair { { 0, 0 }, { 0, 0 } }, common_elevated_ground_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 普通高地(飞坡起点那个高地) common_elevated_ground_final = PointPair { { 0, 0 }, { 0, 0 } }, }, @@ -83,6 +170,47 @@ local function create_default_blackboard() return result.user.bullet >= result.rule.bullet_ready end, + base_in_danger = function() + return result.game.base_health <= result.rule.base_health_red_line + end, + + outpost_survival = function() + return result.game.outpost_health > 0 + end, + + dart_hit_first_time = function() + local current = result.game.our_dart_number_of_hits + + if last_our_dart_number_of_hits == nil then + last_our_dart_number_of_hits = current + return false + end + + local triggered = last_our_dart_number_of_hits == 0 and current == 1 + last_our_dart_number_of_hits = current + return triggered + end, + + fortress_occupied = function() + return result.game.fortress_occupied + end, + + big_energy_mechanism_activated = function() + return result.game.big_energy_mechanism_activated + end, + + small_energy_mechanism_activated = function() + return result.game.small_energy_mechanism_activated + end, + + game_close_to_end = function() + return result.game.remaining_time <= result.rule.time_of_the_competition_red_line + end, + + can_confirm_free_revive = function () + return result.game.can_confirm_free_revive + end, + --- @param target {x: number, y: number} --- @param tolerance? number|{x: number, y: number} near = function(target, tolerance)