Skip to content
Draft
Show file tree
Hide file tree
Changes from 4 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
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -215,6 +215,9 @@ log/
.pyenv2/*
.pyenv3/*

# Generated parameter library files
**/vision_parameters.py

ansible_robots/*
doc_internal/*
doku/*
Expand Down
111 changes: 0 additions & 111 deletions bitbots_vision/bitbots_vision/params.py

This file was deleted.

87 changes: 56 additions & 31 deletions bitbots_vision/bitbots_vision/vision.py
Original file line number Diff line number Diff line change
@@ -1,18 +1,15 @@
#! /usr/bin/env python3
from copy import deepcopy
from typing import Optional

import rclpy
from ament_index_python.packages import get_package_share_directory
from cv_bridge import CvBridge
from rcl_interfaces.msg import SetParametersResult
from rclpy.experimental.events_executor import EventsExecutor
from rclpy.node import Node
from sensor_msgs.msg import Image

from bitbots_vision.vision_modules import debug, ros_utils, yoeo

from .params import gen
from bitbots_vision.vision_parameters import bitbots_vision as parameters

logger = rclpy.logging.get_logger("bitbots_vision")

Expand All @@ -39,20 +36,22 @@ def __init__(self) -> None:

logger.debug(f"Entering {self.__class__.__name__} constructor")

# Setup parameter listener directly
self.param_listener = parameters.ParamListener(self)
self.config = self.param_listener.get_params()

self._package_path = get_package_share_directory("bitbots_vision")

yoeo.YOEOObjectManager.set_package_directory(self._package_path)

self._config: dict = {}
self._cv_bridge = CvBridge()

self._sub_image = None

self._vision_components: list[yoeo.AbstractVisionComponent] = []
self._debug_image: Optional[debug.DebugImage] = None

# Setup reconfiguration
gen.declare_params(self)
# Setup reconfiguration callback
self.add_on_set_parameters_callback(self._dynamic_reconfigure_callback)

# Add general params
Expand All @@ -61,32 +60,54 @@ def __init__(self) -> None:
# Update team color
ros_utils.update_own_team_color(self)

self._dynamic_reconfigure_callback(self.get_parameters_by_prefix("").values())
# Configure vision with initial parameters
self._configure_vision_from_config()

logger.debug(f"Leaving {self.__class__.__name__} constructor")

def _configure_vision_from_config(self) -> None:
"""
Configure vision components using the current config.
"""
self._configure_vision(self.config)

def _dynamic_reconfigure_callback(self, params) -> SetParametersResult:
"""
Callback for the dynamic reconfigure configuration.

:param dict params: new config
:param params: list of changed parameters
"""
new_config = self._get_updated_config_with(params)
self._configure_vision(new_config)
self._config = new_config
# Update the config from the parameter listener
self.config = self.param_listener.get_params()

# Configure vision with the updated config
self._configure_vision_from_config()

return SetParametersResult(successful=True)

def _get_updated_config_with(self, params) -> dict:
new_config = deepcopy(self._config)
for param in params:
new_config[param.name] = param.value
return new_config

def _configure_vision(self, new_config: dict) -> None:
yoeo.YOEOObjectManager.configure(new_config)

debug_image = debug.DebugImage(new_config["component_debug_image_active"])
def _configure_vision(self, config) -> None:
# Create a minimal config dict for compatibility with existing subsystems
# TODO: Update subsystems to use dot notation and remove this compatibility layer
config_dict = {
"component_ball_detection_active": config.component_ball_detection_active,
"component_debug_image_active": config.component_debug_image_active,
"component_field_detection_active": config.component_field_detection_active,
"component_goalpost_detection_active": config.component_goalpost_detection_active,
"component_line_detection_active": config.component_line_detection_active,
"component_robot_detection_active": config.component_robot_detection_active,
"ROS_img_msg_topic": config.ROS_img_msg_topic,
"yoeo_model_path": config.yoeo_model_path,
"yoeo_nms_threshold": config.yoeo_nms_threshold,
"yoeo_conf_threshold": config.yoeo_conf_threshold,
"yoeo_framework": config.yoeo_framework,
"ball_candidate_rating_threshold": config.ball_candidate_rating_threshold,
"ball_candidate_max_count": config.ball_candidate_max_count,
"caching": config.caching,
}

yoeo.YOEOObjectManager.configure(config_dict)

debug_image = debug.DebugImage(config.component_debug_image_active)
self._debug_image = debug_image

def make_vision_component(
Expand All @@ -96,39 +117,43 @@ def make_vision_component(
node=self,
yoeo_handler=yoeo.YOEOObjectManager.get(),
debug_image=debug_image,
config=new_config,
config=config_dict, # Still passing dict for compatibility
**kwargs,
)

self._vision_components = [make_vision_component(yoeo.YOEOComponent)]

if new_config["component_ball_detection_active"]:
if config.component_ball_detection_active:
self._vision_components.append(make_vision_component(yoeo.BallDetectionComponent))
if new_config["component_robot_detection_active"]:
if config.component_robot_detection_active:
self._vision_components.append(
make_vision_component(
yoeo.RobotDetectionComponent,
team_color_detection_supported=yoeo.YOEOObjectManager.is_team_color_detection_supported(),
)
)
if new_config["component_goalpost_detection_active"]:
if config.component_goalpost_detection_active:
self._vision_components.append(make_vision_component(yoeo.GoalpostDetectionComponent))
if new_config["component_line_detection_active"]:
if config.component_line_detection_active:
self._vision_components.append(make_vision_component(yoeo.LineDetectionComponent))
if new_config["component_field_detection_active"]:
if config.component_field_detection_active:
self._vision_components.append(make_vision_component(yoeo.FieldDetectionComponent))
if new_config["component_debug_image_active"]:
if config.component_debug_image_active:
self._vision_components.append(make_vision_component(yoeo.DebugImageComponent))

# For the subscriber update, we'll pass the last config dict or None for the first time
old_config_dict = getattr(self, '_last_config_dict', None)
self._sub_image = ros_utils.create_or_update_subscriber(
self,
self._config,
new_config,
old_config_dict,
config_dict,
self._sub_image,
"ROS_img_msg_topic",
Image,
callback=self._run_vision_pipeline,
)
# Remember this config for next time
self._last_config_dict = config_dict.copy()

@profile
def _run_vision_pipeline(self, image_msg: Image) -> None:
Expand Down
Loading
Loading