Skip to content
Draft
Show file tree
Hide file tree
Changes from 3 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/

ansible_robots/*
doc_internal/*
doku/*
Expand Down
18 changes: 16 additions & 2 deletions bitbots_vision/bitbots_vision/__init__.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,18 @@
# Setting up runtime type checking for this package
from beartype.claw import beartype_this_package
try:
from beartype.claw import beartype_this_package
beartype_this_package()
except ImportError:
# beartype not available, skip type checking
pass

beartype_this_package()
from rclpy.node import Node

from bitbots_vision.vision_parameters import bitbots_vision as parameters


class NodeWithConfig(Node):
def __init__(self, name: str) -> None:
super().__init__(name)
self.param_listener = parameters.ParamListener(self)
self.config = self.param_listener.get_params()
111 changes: 0 additions & 111 deletions bitbots_vision/bitbots_vision/params.py

This file was deleted.

81 changes: 61 additions & 20 deletions bitbots_vision/bitbots_vision/vision.py
Original file line number Diff line number Diff line change
@@ -1,19 +1,16 @@
#! /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 import NodeWithConfig
from bitbots_vision.vision_modules import debug, ros_utils, yoeo

from .params import gen

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

try:
Expand All @@ -26,7 +23,7 @@ def profile(func):
logger.info("No Profiling available")


class YOEOVision(Node):
class YOEOVision(NodeWithConfig):
"""
The Vision is the main ROS-node for handling all tasks related to image processing.

Expand All @@ -43,16 +40,14 @@ def __init__(self) -> None:

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 - now we use the generated parameter listener
self.add_on_set_parameters_callback(self._dynamic_reconfigure_callback)

# Add general params
Expand All @@ -61,28 +56,70 @@ 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 _config_to_dict(self) -> dict:
"""
Convert the generated parameter config object to a dictionary for compatibility
with existing code that expects dictionary access.
"""
return {
# Component activation parameters
"component_ball_detection_active": self.config.component_ball_detection_active,
"component_debug_image_active": self.config.component_debug_image_active,
"component_field_detection_active": self.config.component_field_detection_active,
"component_goalpost_detection_active": self.config.component_goalpost_detection_active,
"component_line_detection_active": self.config.component_line_detection_active,
"component_robot_detection_active": self.config.component_robot_detection_active,

# ROS topic parameters
"ROS_img_msg_topic": self.config.ROS_img_msg_topic,
"ROS_ball_msg_topic": self.config.ROS_ball_msg_topic,
"ROS_goal_posts_msg_topic": self.config.ROS_goal_posts_msg_topic,
"ROS_robot_msg_topic": self.config.ROS_robot_msg_topic,
"ROS_line_msg_topic": self.config.ROS_line_msg_topic,
"ROS_line_mask_msg_topic": self.config.ROS_line_mask_msg_topic,
"ROS_debug_image_msg_topic": self.config.ROS_debug_image_msg_topic,
"ROS_field_mask_image_msg_topic": self.config.ROS_field_mask_image_msg_topic,

# YOEO model parameters
"yoeo_model_path": self.config.yoeo_model_path,
"yoeo_nms_threshold": self.config.yoeo_nms_threshold,
"yoeo_conf_threshold": self.config.yoeo_conf_threshold,
"yoeo_framework": self.config.yoeo_framework,

# Ball detection parameters
"ball_candidate_rating_threshold": self.config.ball_candidate_rating_threshold,
"ball_candidate_max_count": self.config.ball_candidate_max_count,

# Caching parameter
"caching": self.config.caching,
}

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

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)

Expand Down Expand Up @@ -120,15 +157,19 @@ def make_vision_component(
if new_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,
old_config_dict,
new_config,
self._sub_image,
"ROS_img_msg_topic",
Image,
callback=self._run_vision_pipeline,
)
# Remember this config for next time
self._last_config_dict = new_config.copy()

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