From 9c6cdfa291403ce2eb18e1c705b43786f28bc3a9 Mon Sep 17 00:00:00 2001 From: shalenikol Date: Tue, 20 May 2025 12:07:15 +0300 Subject: [PATCH] del scenario,gym_gz from env_manager + refactoring --- env_manager/env_manager/package.xml | 4 ++-- rbss_aruco_pe/package.xml | 4 ++-- rbss_aruco_pe/rbs_package.json | 12 ++++++++++++ rbss_aruco_pe/scripts/aruco_node_lc.py | 11 ----------- rbss_objectdetection/scripts/od_yolo_lc.py | 6 ++++++ 5 files changed, 22 insertions(+), 15 deletions(-) diff --git a/env_manager/env_manager/package.xml b/env_manager/env_manager/package.xml index f479e44..effa29f 100644 --- a/env_manager/env_manager/package.xml +++ b/env_manager/env_manager/package.xml @@ -7,8 +7,8 @@ narmak Apache-2.0 - scenario - gym_gz + + ament_copyright ament_flake8 diff --git a/rbss_aruco_pe/package.xml b/rbss_aruco_pe/package.xml index b70b077..09c2a6f 100644 --- a/rbss_aruco_pe/package.xml +++ b/rbss_aruco_pe/package.xml @@ -17,8 +17,8 @@ geometry_msgs lifecycle_msgs rbs_skill_interfaces - open3d - opencv + + tf_transformations ament_lint_auto diff --git a/rbss_aruco_pe/rbs_package.json b/rbss_aruco_pe/rbs_package.json index f8cf87c..489a323 100644 --- a/rbss_aruco_pe/rbs_package.json +++ b/rbss_aruco_pe/rbs_package.json @@ -37,6 +37,18 @@ ], "typeAction": "ACTION" }, + { "name": "isAruco", "type": "if", "typeAction": "CONDITION", + "param": [ + { + "type": "formBuilder", + "dependency": { + "output": { + "aruco_id": "25" + } + } + } + ] + }, { "name": "arucoStop", "type": "stop", "param": [], "typeAction": "ACTION" } ], "topicsOut": [ diff --git a/rbss_aruco_pe/scripts/aruco_node_lc.py b/rbss_aruco_pe/scripts/aruco_node_lc.py index 73e7ff7..edb3229 100755 --- a/rbss_aruco_pe/scripts/aruco_node_lc.py +++ b/rbss_aruco_pe/scripts/aruco_node_lc.py @@ -34,14 +34,12 @@ Parameters: Version: 2025-04-16 """ - # ROS2 imports import rclpy from rclpy.qos import qos_profile_sensor_data from cv_bridge import CvBridge import message_filters from rclpy.lifecycle import Node -# from rclpy.lifecycle import Publisher from rclpy.lifecycle import LifecycleState from rclpy.lifecycle import TransitionCallbackReturn @@ -205,9 +203,6 @@ class ArucoLcNode(Node): self.depth_image_topic = topic_name else: self.image_topic = topic_name - # elif par["type"] == "formBuilder": - # self.objName = dependency["output"]["object_name"] - # val = dependency["output"]["process"]["selectProcess"]["value"] # camera info topic for the camera calibration parameters self.info_sub = self.create_subscription(CameraInfo, self.info_topic, self.info_callback, qos_profile_sensor_data) @@ -368,12 +363,6 @@ class ArucoLcNode(Node): self.image_pub.publish(self.bridge.cv2_to_imgmsg(frame, "rgb8")) def main(): - # rclpy.init() - # node = ArucoNode() - # rclpy.spin(node) - - # node.destroy_node() - # rclpy.shutdown() rclpy.init() executor = rclpy.executors.SingleThreadedExecutor() diff --git a/rbss_objectdetection/scripts/od_yolo_lc.py b/rbss_objectdetection/scripts/od_yolo_lc.py index 2fc85a3..929bb99 100755 --- a/rbss_objectdetection/scripts/od_yolo_lc.py +++ b/rbss_objectdetection/scripts/od_yolo_lc.py @@ -4,6 +4,7 @@ ROS 2 program for Object Detection @shalenikol release 0.4 + ... """ from typing import Optional @@ -49,6 +50,7 @@ class ObjectDetection(Node): self._is_image_mode = False self.yolov8_weights_file = "" self.model = None + self.is_detection = False # object detection indicator in the frame # for other nodes kwargs["allow_undeclared_parameters"] = True @@ -100,6 +102,8 @@ class ObjectDetection(Node): # res = self._cli_getstate.call(req) # the program freezes id_,_ = self._state_machine.current_state _is = (id_ == State.PRIMARY_STATE_ACTIVE) + elif request.command == "isDetection": + _is = self.is_detection response.ok = _is return response @@ -206,6 +210,7 @@ class ObjectDetection(Node): return msg = BoundBox() msg.is_detection = False + self.is_detection = False #from ultralytics.engine.results cconf = self._threshold # threshold bb = None @@ -218,6 +223,7 @@ class ObjectDetection(Node): bb = c if bb: msg.is_detection = True + self.is_detection = True msg.name = self.objName msg.x = float(bb.xywhn[0,0]) msg.y = float(bb.xywhn[0,1])