Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
194 changes: 187 additions & 7 deletions src/cxx/component.cc
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#include <string>
#if defined(__clang__)
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
#elif defined(__GNUC__)
Expand All @@ -7,7 +8,9 @@
#include "cxx/context.hh"
#include "cxx/util/navigation/navigation.hh"
#include "cxx/util/node_mixin.hh"

#include <algorithm>
#include <chrono>
#include <cstdint>
#include <filesystem>

#include <Eigen/Geometry>
Expand Down Expand Up @@ -52,6 +55,12 @@ class Navigation
OutputInterface<ChassisMode> chassis_behavior;
OutputInterface<Eigen::Vector2d> chassis_speed;
OutputInterface<Eigen::Vector2d> gimbal_speed;
OutputInterface<bool> sentry_decision_enabled;
OutputInterface<std::uint16_t> sentry_bullet_exchange_value;
OutputInterface<std::uint8_t> requested_mode;
OutputInterface<bool> 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);
Expand All @@ -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<std::uint16_t>(amount);
activate_decision();
}

auto switch_mode(int mode) -> void {
if (mode < 1 || mode > 3)
return;

reset_all_decisions();
*requested_mode = static_cast<std::uint8_t>(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();
}
Comment thread
coderabbitai[bot] marked this conversation as resolved.

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;

Expand Down Expand Up @@ -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() {
Expand Down Expand Up @@ -156,20 +239,112 @@ class Navigation
auto lua_sync() {
const auto [x, y, yaw] = navigation.check_position();

auto read_context =
[]<typename T>(const details::Context::InputInterface<T>& input, T fallback) -> T {
if (input.ready())
return *input;

return fallback;
};

auto user = lua_blackboard["user"].get<sol::table>();
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<sol::table>();
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<int>(
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<sol::table>(),
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<sol::table>(),
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<sol::table>(),
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<sol::table>(),
read_context(context.ally_engineer_position_x, 0.0),
read_context(context.ally_engineer_position_y, 0.0));

game["robot_id"] = static_cast<int>(
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<sol::table>();
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<sol::table>();
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<int>(read_context(context.map_command_event_keyboard, std::uint8_t{0}));
map_command["target_robot_id"] = static_cast<int>(
read_context(context.map_command_event_target_robot_id, std::uint8_t{0}));
map_command["source"] =
static_cast<int>(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<sol::table>();
meta["timestamp"] = this->now().seconds();
Expand Down Expand Up @@ -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};
Expand Down
81 changes: 81 additions & 0 deletions src/cxx/context.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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";
Expand Down
Loading