Skip to content
Merged
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
5 changes: 0 additions & 5 deletions ateam_kenobi/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,7 @@ find_package(ateam_geometry REQUIRED)
find_package(control_toolbox REQUIRED)
find_package(ompl REQUIRED)
find_package(angles REQUIRED)
find_package(OpenCV REQUIRED)
find_package(nlohmann_json REQUIRED)
find_package(ateam_spatial REQUIRED)

add_library(kenobi_node_component SHARED
src/kenobi_node.cpp
Expand Down Expand Up @@ -60,7 +58,6 @@ target_sources(kenobi_node_component PRIVATE
src/plays/kickoff_plays/offense/our_kickoff_prep_play.cpp
src/plays/passing_plays/pass_to_lane_play.cpp
src/plays/passing_plays/pass_to_segment_play.cpp
src/plays/passing_plays/spatial_pass_play.cpp
src/plays/stop_plays/default_stop_play.cpp
src/plays/stop_plays/defensive_stop_play.cpp
src/plays/stop_plays/offensive_stop_play.cpp
Expand Down Expand Up @@ -131,9 +128,7 @@ ament_target_dependencies(
"control_toolbox"
"OMPL"
"angles"
OpenCV
nlohmann_json
ateam_spatial
)
rclcpp_components_register_node(
kenobi_node_component
Expand Down
2 changes: 0 additions & 2 deletions ateam_kenobi/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,6 @@
<depend>ompl</depend>
<depend>nlohmann-json-dev</depend>
<depend>angles</depend>
<depend>libopencv-dev</depend>
<depend>ateam_spatial</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
2 changes: 0 additions & 2 deletions ateam_kenobi/src/core/play_selector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,8 +89,6 @@ PlaySelector::PlaySelector(rclcpp::Node & node)
addPlay<PassToLanePlay>(
"PassRightBackwardPlay", stp_options, play_helpers::lanes::Lane::Right,
PassToLanePlay::PassDirection::Backward);
addPlay<TestSpatialMapPlay>(stp_options);
addPlay<SpatialPassPlay>(stp_options);
addPlay<FreeKickOnGoalPlay>(stp_options);
addPlay<TestPassPlay>(stp_options);
addPlay<TestPivotPlay>(stp_options);
Expand Down
3 changes: 0 additions & 3 deletions ateam_kenobi/src/core/types/world.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
#include <optional>
#include <array>
#include <chrono>
#include <ateam_spatial/spatial_evaluator.hpp>

#include "core/types/ball.hpp"
#include "core/types/field.hpp"
Expand Down Expand Up @@ -55,8 +54,6 @@ struct World

// Holds the ID of the robot not allowed to touch the ball, if any
std::optional<int> double_touch_forbidden_id_;

ateam_spatial::SpatialEvaluator * spatial_evaluator;
};
} // namespace ateam_kenobi

Expand Down
98 changes: 0 additions & 98 deletions ateam_kenobi/src/core/visualization/overlays.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
#include <algorithm>
#include <memory>
#include <utility>
#include <opencv2/opencv.hpp>

namespace ateam_kenobi::visualization
{
Expand Down Expand Up @@ -257,103 +256,6 @@ void Overlays::drawArrows(
addOverlay(msg);
}

void Overlays::drawHeatmap(
const std::string & name, const ateam_geometry::Rectangle & bounds,
const cv::Mat & data, const uint8_t alpha, const uint32_t lifetime)
{
ateam_msgs::msg::Overlay msg;
msg.ns = ns_;
msg.name = name;
msg.visible = true;
msg.type = ateam_msgs::msg::Overlay::HEATMAP;
msg.command = ateam_msgs::msg::Overlay::REPLACE;
msg.lifetime = lifetime;
msg.position.x = std::midpoint(bounds.xmin(), bounds.xmax());
msg.position.y = std::midpoint(bounds.ymin(), bounds.ymax());
msg.scale.x = bounds.xmax() - bounds.xmin();
msg.scale.y = bounds.ymax() - bounds.ymin();
msg.heatmap_resolution_width = data.cols;
msg.heatmap_resolution_height = data.rows;
msg.heatmap_alpha = {alpha};
msg.heatmap_data.reserve(data.rows * data.cols);
if(!data.empty()) {
switch(data.type()) {
case CV_8UC1:
std::copy(data.begin<uint8_t>(), data.end<uint8_t>(), std::back_inserter(msg.heatmap_data));
break;
case CV_32FC1:
{
cv::Mat byte_data{data.rows, data.cols, CV_8UC1};
cv::normalize(data, byte_data, 0, 255, cv::NORM_MINMAX, CV_8UC1);
std::copy(byte_data.begin<uint8_t>(), byte_data.end<uint8_t>(),
std::back_inserter(msg.heatmap_data));
break;
}
default:
throw std::runtime_error("Unsupported heatmap data type: " + std::to_string(data.type()));
}
}
addOverlay(msg);
}

void Overlays::drawHeatmap(
const std::string & name, const ateam_geometry::Rectangle & bounds,
const cv::Mat & data, const cv::Mat & alpha, const uint32_t lifetime)
{
ateam_msgs::msg::Overlay msg;
msg.ns = ns_;
msg.name = name;
msg.visible = true;
msg.type = ateam_msgs::msg::Overlay::HEATMAP;
msg.command = ateam_msgs::msg::Overlay::REPLACE;
msg.lifetime = lifetime;
msg.position.x = std::midpoint(bounds.xmin(), bounds.xmax());
msg.position.y = std::midpoint(bounds.ymin(), bounds.ymax());
msg.scale.x = bounds.xmax() - bounds.xmin();
msg.scale.y = bounds.ymax() - bounds.ymin();
msg.heatmap_resolution_width = data.cols;
msg.heatmap_resolution_height = data.rows;
msg.heatmap_alpha.reserve(alpha.rows * alpha.cols);
if(!alpha.empty()) {
switch(alpha.type()) {
case CV_8UC1:
std::copy(alpha.begin<uint8_t>(), alpha.end<uint8_t>(),
std::back_inserter(msg.heatmap_alpha));
break;
case CV_32FC1:
{
cv::Mat byte_alpha{alpha.rows, alpha.cols, CV_8UC1};
cv::normalize(alpha, byte_alpha, 0, 255, cv::NORM_MINMAX, CV_8UC1);
std::copy(byte_alpha.begin<uint8_t>(), byte_alpha.end<uint8_t>(),
std::back_inserter(msg.heatmap_alpha));
break;
}
default:
throw std::runtime_error("Unsupported heatmap alpha type: " + std::to_string(data.type()));
}
}
msg.heatmap_data.reserve(data.rows * data.cols);
if(!data.empty()) {
switch(data.type()) {
case CV_8UC1:
std::copy(data.begin<uint8_t>(), data.end<uint8_t>(), std::back_inserter(msg.heatmap_data));
break;
case CV_32FC1:
{
cv::Mat byte_data{data.rows, data.cols, CV_8UC1};
cv::normalize(data, byte_data, 0, 255, cv::NORM_MINMAX, CV_8UC1);
std::copy(byte_data.begin<uint8_t>(), byte_data.end<uint8_t>(),
std::back_inserter(msg.heatmap_data));
break;
}
default:
throw std::runtime_error("Unsupported heatmap data type: " + std::to_string(data.type()));
}
}
addOverlay(msg);
}


void Overlays::drawHeatmap(
const std::string & name, const ateam_geometry::Rectangle & bounds,
const std::vector<uint8_t> & data, const std::size_t resolution_width,
Expand Down
9 changes: 0 additions & 9 deletions ateam_kenobi/src/core/visualization/overlays.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
#include <ateam_msgs/msg/overlay_array.hpp>
#include <ateam_geometry/arc.hpp>
#include <ateam_geometry/types.hpp>
#include <opencv2/core/mat.hpp>

namespace ateam_kenobi::visualization
{
Expand Down Expand Up @@ -86,14 +85,6 @@ class Overlays
const std::string & stroke_color = "blue", const uint8_t stroke_width = 5,
const uint32_t lifetime = kDefaultLifetime);

void drawHeatmap(
const std::string & name, const ateam_geometry::Rectangle & bounds,
const cv::Mat & data, const uint8_t alpha = 255, const uint32_t lifetime = kDefaultLifetime);

void drawHeatmap(
const std::string & name, const ateam_geometry::Rectangle & bounds,
const cv::Mat & data, const cv::Mat & alpha, const uint32_t lifetime = kDefaultLifetime);

void drawHeatmap(
const std::string & name, const ateam_geometry::Rectangle & bounds,
const std::vector<uint8_t> & data, const std::size_t resolution_width,
Expand Down
40 changes: 0 additions & 40 deletions ateam_kenobi/src/kenobi_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@
#include "plays/halt_play.hpp"
#include "core/defense_area_enforcement.hpp"
#include "core/joystick_enforcer.hpp"
#include <ateam_spatial/spatial_evaluator.hpp>
#include "core/fps_tracker.hpp"

namespace ateam_kenobi
Expand All @@ -74,8 +73,6 @@ class KenobiNode : public rclcpp::Node
overlays_(""),
game_controller_listener_(*this)
{
world_.spatial_evaluator = &spatial_evaluator_;

initialize_robot_ids();

declare_parameter<bool>("use_world_velocities", false);
Expand Down Expand Up @@ -173,7 +170,6 @@ class KenobiNode : public rclcpp::Node
}

private:
ateam_spatial::SpatialEvaluator spatial_evaluator_;
World world_;
PlaySelector play_selector_;
InPlayEval in_play_eval_;
Expand Down Expand Up @@ -414,7 +410,6 @@ class KenobiNode : public rclcpp::Node
}
in_play_eval_.Update(world_);
double_touch_eval_.update(world_, overlays_);
UpdateSpatialEvaluator();
if (get_parameter("use_emulated_ballsense").as_bool()) {
ballsense_emulator_.Update(world_);
}
Expand Down Expand Up @@ -505,41 +500,6 @@ class KenobiNode : public rclcpp::Node
{
return ateam_common::getCacheDirectory() / "kenobi";
}

void UpdateSpatialEvaluator()
{
ateam_spatial::FieldDimensions field{
world_.field.field_width,
world_.field.field_length,
world_.field.goal_width,
world_.field.goal_depth,
world_.field.boundary_width,
world_.field.defense_area_width,
world_.field.defense_area_depth
};
ateam_spatial::Ball ball{
static_cast<float>(world_.ball.pos.x()),
static_cast<float>(world_.ball.pos.y()),
static_cast<float>(world_.ball.vel.x()),
static_cast<float>(world_.ball.vel.y())
};
auto make_spatial_robot = [](const Robot & robot){
return ateam_spatial::Robot{
robot.visible,
static_cast<float>(robot.pos.x()),
static_cast<float>(robot.pos.y()),
static_cast<float>(robot.theta),
static_cast<float>(robot.vel.x()),
static_cast<float>(robot.vel.y()),
static_cast<float>(robot.omega)
};
};
std::array<ateam_spatial::Robot, 16> our_robots;
std::ranges::transform(world_.our_robots, our_robots.begin(), make_spatial_robot);
std::array<ateam_spatial::Robot, 16> their_robots;
std::ranges::transform(world_.their_robots, their_robots.begin(), make_spatial_robot);
spatial_evaluator_.UpdateMaps(field, ball, our_robots, their_robots);
}
};

} // namespace ateam_kenobi
Expand Down
1 change: 0 additions & 1 deletion ateam_kenobi/src/plays/passing_plays/all_passing_plays.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,5 @@
#include "pass_to_lane_play.hpp"
#include "pass_to_segment_play.hpp"
#include "segment_passing_target_funcs.hpp"
#include "spatial_pass_play.hpp"

#endif // PLAYS__PASSING_PLAYS__ALL_PASSING_PLAYS_HPP_
Loading