del scenario,gym_gz from env_manager + refactoring
This commit is contained in:
parent
8d83e3d708
commit
9c6cdfa291
5 changed files with 22 additions and 15 deletions
|
@ -7,8 +7,8 @@
|
||||||
<maintainer email="ur.narmak@gmail.com">narmak</maintainer>
|
<maintainer email="ur.narmak@gmail.com">narmak</maintainer>
|
||||||
<license>Apache-2.0</license>
|
<license>Apache-2.0</license>
|
||||||
|
|
||||||
<depend>scenario</depend>
|
<!-- <depend>scenario</depend> -->
|
||||||
<depend>gym_gz</depend>
|
<!-- <depend>gym_gz</depend> -->
|
||||||
|
|
||||||
<test_depend>ament_copyright</test_depend>
|
<test_depend>ament_copyright</test_depend>
|
||||||
<test_depend>ament_flake8</test_depend>
|
<test_depend>ament_flake8</test_depend>
|
||||||
|
|
|
@ -17,8 +17,8 @@
|
||||||
<depend>geometry_msgs</depend>
|
<depend>geometry_msgs</depend>
|
||||||
<depend>lifecycle_msgs</depend>
|
<depend>lifecycle_msgs</depend>
|
||||||
<depend>rbs_skill_interfaces</depend>
|
<depend>rbs_skill_interfaces</depend>
|
||||||
<depend>open3d</depend>
|
<!-- <depend>open3d</depend> -->
|
||||||
<depend>opencv</depend>
|
<!-- <depend>opencv</depend> -->
|
||||||
<depend>tf_transformations</depend>
|
<depend>tf_transformations</depend>
|
||||||
|
|
||||||
<test_depend>ament_lint_auto</test_depend>
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
|
|
|
@ -37,6 +37,18 @@
|
||||||
],
|
],
|
||||||
"typeAction": "ACTION"
|
"typeAction": "ACTION"
|
||||||
},
|
},
|
||||||
|
{ "name": "isAruco", "type": "if", "typeAction": "CONDITION",
|
||||||
|
"param": [
|
||||||
|
{
|
||||||
|
"type": "formBuilder",
|
||||||
|
"dependency": {
|
||||||
|
"output": {
|
||||||
|
"aruco_id": "25"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
]
|
||||||
|
},
|
||||||
{ "name": "arucoStop", "type": "stop", "param": [], "typeAction": "ACTION" }
|
{ "name": "arucoStop", "type": "stop", "param": [], "typeAction": "ACTION" }
|
||||||
],
|
],
|
||||||
"topicsOut": [
|
"topicsOut": [
|
||||||
|
|
|
@ -34,14 +34,12 @@ Parameters:
|
||||||
|
|
||||||
Version: 2025-04-16
|
Version: 2025-04-16
|
||||||
"""
|
"""
|
||||||
|
|
||||||
# ROS2 imports
|
# ROS2 imports
|
||||||
import rclpy
|
import rclpy
|
||||||
from rclpy.qos import qos_profile_sensor_data
|
from rclpy.qos import qos_profile_sensor_data
|
||||||
from cv_bridge import CvBridge
|
from cv_bridge import CvBridge
|
||||||
import message_filters
|
import message_filters
|
||||||
from rclpy.lifecycle import Node
|
from rclpy.lifecycle import Node
|
||||||
# from rclpy.lifecycle import Publisher
|
|
||||||
from rclpy.lifecycle import LifecycleState
|
from rclpy.lifecycle import LifecycleState
|
||||||
from rclpy.lifecycle import TransitionCallbackReturn
|
from rclpy.lifecycle import TransitionCallbackReturn
|
||||||
|
|
||||||
|
@ -205,9 +203,6 @@ class ArucoLcNode(Node):
|
||||||
self.depth_image_topic = topic_name
|
self.depth_image_topic = topic_name
|
||||||
else:
|
else:
|
||||||
self.image_topic = topic_name
|
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
|
# 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)
|
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"))
|
self.image_pub.publish(self.bridge.cv2_to_imgmsg(frame, "rgb8"))
|
||||||
|
|
||||||
def main():
|
def main():
|
||||||
# rclpy.init()
|
|
||||||
# node = ArucoNode()
|
|
||||||
# rclpy.spin(node)
|
|
||||||
|
|
||||||
# node.destroy_node()
|
|
||||||
# rclpy.shutdown()
|
|
||||||
rclpy.init()
|
rclpy.init()
|
||||||
|
|
||||||
executor = rclpy.executors.SingleThreadedExecutor()
|
executor = rclpy.executors.SingleThreadedExecutor()
|
||||||
|
|
|
@ -4,6 +4,7 @@
|
||||||
ROS 2 program for Object Detection
|
ROS 2 program for Object Detection
|
||||||
|
|
||||||
@shalenikol release 0.4
|
@shalenikol release 0.4
|
||||||
|
...
|
||||||
"""
|
"""
|
||||||
|
|
||||||
from typing import Optional
|
from typing import Optional
|
||||||
|
@ -49,6 +50,7 @@ class ObjectDetection(Node):
|
||||||
self._is_image_mode = False
|
self._is_image_mode = False
|
||||||
self.yolov8_weights_file = ""
|
self.yolov8_weights_file = ""
|
||||||
self.model = None
|
self.model = None
|
||||||
|
self.is_detection = False # object detection indicator in the frame
|
||||||
|
|
||||||
# for other nodes
|
# for other nodes
|
||||||
kwargs["allow_undeclared_parameters"] = True
|
kwargs["allow_undeclared_parameters"] = True
|
||||||
|
@ -100,6 +102,8 @@ class ObjectDetection(Node):
|
||||||
# res = self._cli_getstate.call(req) # the program freezes
|
# res = self._cli_getstate.call(req) # the program freezes
|
||||||
id_,_ = self._state_machine.current_state
|
id_,_ = self._state_machine.current_state
|
||||||
_is = (id_ == State.PRIMARY_STATE_ACTIVE)
|
_is = (id_ == State.PRIMARY_STATE_ACTIVE)
|
||||||
|
elif request.command == "isDetection":
|
||||||
|
_is = self.is_detection
|
||||||
response.ok = _is
|
response.ok = _is
|
||||||
return response
|
return response
|
||||||
|
|
||||||
|
@ -206,6 +210,7 @@ class ObjectDetection(Node):
|
||||||
return
|
return
|
||||||
msg = BoundBox()
|
msg = BoundBox()
|
||||||
msg.is_detection = False
|
msg.is_detection = False
|
||||||
|
self.is_detection = False
|
||||||
#from ultralytics.engine.results
|
#from ultralytics.engine.results
|
||||||
cconf = self._threshold # threshold
|
cconf = self._threshold # threshold
|
||||||
bb = None
|
bb = None
|
||||||
|
@ -218,6 +223,7 @@ class ObjectDetection(Node):
|
||||||
bb = c
|
bb = c
|
||||||
if bb:
|
if bb:
|
||||||
msg.is_detection = True
|
msg.is_detection = True
|
||||||
|
self.is_detection = True
|
||||||
msg.name = self.objName
|
msg.name = self.objName
|
||||||
msg.x = float(bb.xywhn[0,0])
|
msg.x = float(bb.xywhn[0,0])
|
||||||
msg.y = float(bb.xywhn[0,1])
|
msg.y = float(bb.xywhn[0,1])
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue