diff --git a/.idea/.gitignore b/.idea/.gitignore
new file mode 100644
index 0000000..35410ca
--- /dev/null
+++ b/.idea/.gitignore
@@ -0,0 +1,8 @@
+# 默认忽略的文件
+/shelf/
+/workspace.xml
+# 基于编辑器的 HTTP 客户端请求
+/httpRequests/
+# Datasource local storage ignored files
+/dataSources/
+/dataSources.local.xml
diff --git a/.idea/inspectionProfiles/profiles_settings.xml b/.idea/inspectionProfiles/profiles_settings.xml
new file mode 100644
index 0000000..105ce2d
--- /dev/null
+++ b/.idea/inspectionProfiles/profiles_settings.xml
@@ -0,0 +1,6 @@
+
+
+
+
+
+
\ No newline at end of file
diff --git a/.idea/misc.xml b/.idea/misc.xml
new file mode 100644
index 0000000..dc9ea49
--- /dev/null
+++ b/.idea/misc.xml
@@ -0,0 +1,4 @@
+
+
+
+
\ No newline at end of file
diff --git a/.idea/modules.xml b/.idea/modules.xml
new file mode 100644
index 0000000..249912e
--- /dev/null
+++ b/.idea/modules.xml
@@ -0,0 +1,8 @@
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/.idea/softwaresystem.iml b/.idea/softwaresystem.iml
new file mode 100644
index 0000000..207a0d7
--- /dev/null
+++ b/.idea/softwaresystem.iml
@@ -0,0 +1,15 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/.idea/vcs.xml b/.idea/vcs.xml
new file mode 100644
index 0000000..35eb1dd
--- /dev/null
+++ b/.idea/vcs.xml
@@ -0,0 +1,6 @@
+
+
+
+
+
+
\ No newline at end of file
diff --git a/HiveCoreR0/src/robot_vision/README.md b/HiveCoreR0/src/robot_vision/README.md
index faa6128..927066d 100644
--- a/HiveCoreR0/src/robot_vision/README.md
+++ b/HiveCoreR0/src/robot_vision/README.md
@@ -47,7 +47,9 @@
ros2 launch detect_part camera_detect.launch.py
- > camera_detect.launch.py 中可以修改部分参数:set_confidence, output_detect_image, checkpoint_name
+ > camera_detect.launch.py 中可以修改部分参数:set_confidence, output_boxes, output_masks, checkpoint_name
+
+ > 坐标系设置为:Z为图像深度,XY平面为图像成象平面
2. 接收位置话题节点:
@@ -55,20 +57,19 @@
3. 位置话题接口:
- interface/msg/PointWithID.msg, PointWithIDArray.msg
+ interface/msg/PoseWithID.msg, PoseWithIDArray.msg
4. 话题名称:
/pose/cv_detect_pose # 位置
/image/detect_image # 目标识别图片
-5. PointWithID.msg:
+5. PoseWithID.msg:
string class_name
int32 class_id
- geometry_msgs/Point[] points
+ geometry_msgs/Pose[] pose_list
-6. PointWithIDArray.msg:
-
- PointWithID[] objects
+6. PoseWithIDArray.msg:
+ PoseWithID[] objects
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/__init__.py b/HiveCoreR0/src/robot_vision/detect_part/detect_part/__init__.py
index e69de29..139597f 100644
--- a/HiveCoreR0/src/robot_vision/detect_part/detect_part/__init__.py
+++ b/HiveCoreR0/src/robot_vision/detect_part/detect_part/__init__.py
@@ -0,0 +1,2 @@
+
+
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/__pycache__/__init__.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/__pycache__/__init__.cpython-310.pyc
index 01cbf0f..449f1a4 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/__pycache__/__init__.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/__pycache__/__init__.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/checkpoint/yolo11n-seg.pt b/HiveCoreR0/src/robot_vision/detect_part/detect_part/checkpoint/yolo11n-seg.pt
new file mode 100644
index 0000000..628f517
Binary files /dev/null and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/checkpoint/yolo11n-seg.pt differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/checkpoint/yolo11s-seg.pt b/HiveCoreR0/src/robot_vision/detect_part/detect_part/checkpoint/yolo11s-seg.pt
new file mode 100644
index 0000000..d7be62d
Binary files /dev/null and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/checkpoint/yolo11s-seg.pt differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/detect.py b/HiveCoreR0/src/robot_vision/detect_part/detect_part/detect.py
index cc52f33..7c53d46 100644
--- a/HiveCoreR0/src/robot_vision/detect_part/detect_part/detect.py
+++ b/HiveCoreR0/src/robot_vision/detect_part/detect_part/detect.py
@@ -1,5 +1,5 @@
import os
-import random
+import math
from collections import defaultdict
import cv2
@@ -14,61 +14,195 @@ from rclpy.node import Node
from message_filters import ApproximateTimeSynchronizer, Subscriber
from sensor_msgs.msg import Image, CameraInfo
-from geometry_msgs.msg import Point
-from interfaces.msg import PointWithID, PointWithIDArray
+from geometry_msgs.msg import Pose, Point, Quaternion
+from interfaces.msg import PoseWithID, PoseWithIDArray
import detect_part
+def iqr(depths, threshold: float = 1.5):
+ if len(depths) < 7:
+ return depths
+ q1 = np.percentile(depths, 25)
+ q3 = np.percentile(depths, 75)
+ iqr_ = q3 - q1
+ lower_bound = q1 - iqr_ * threshold
+ upper_bound = q3 + iqr_ * threshold
+ iqr_depths = depths[(depths >= lower_bound) & (depths <= upper_bound)]
+ return iqr_depths
+
+
+def get_nine_patch_samples(depth_img, u, v, width, height):
+ ws = [int(round(-width/4)), 0, int(round(width/4))]
+ hs = [int(round(-height/4)), 0, int(round(height/4))]
+
+ window_size = 25
+ half = window_size // 2
+
+ patch = []
+ for w in ws:
+ for h in hs:
+ patch.append(
+ depth_img[int(max(0, v + h - half)):int(min(v + h + half + 1, depth_img.shape[0])):2,
+ int(max(0, u + w - half)):int(min(u + w + half + 1, depth_img.shape[1])):2].flatten())
+
+ return np.concatenate(patch)
+
+
+def calculate_coordinate(self, depth_img: np.ndarray, camera_info, u, v, width: int, height: int) -> tuple[float, float, float]:
+ u = int(round(u))
+ v = int(round(v))
+
+ _cx, _cy, _fx, _fy = camera_info
+
+ if not (0 <= v < depth_img.shape[0] and 0 <= u < depth_img.shape[1]):
+ self.get_logger().warning(f'Calculate coordinate error: u={u}, v={v}')
+ return 0.0, 0.0, 0.0
+
+ window_size = 39
+ half = window_size // 2
+
+ patch = depth_img[max(0, v - half):v + half + 1, max(0, u - half):u + half + 1:2].flatten()
+ valid_depths = patch[patch > 0]
+
+ if len(valid_depths) == 0:
+ patch = get_nine_patch_samples(depth_img, u, v, width, height)
+ valid_depths = patch[patch > 0]
+
+ if len(valid_depths) == 0:
+ self.get_logger().warning(f'No valid depth in window at ({u}, {v})')
+ return 0.0, 0.0, 0.0
+
+ valid_depths = iqr(valid_depths)
+
+ depth = np.median(valid_depths) / 1e3
+ z = depth
+
+ x = -(u - _cx) * z / _fx
+ y = -(v - _cy) * z / _fy
+
+ return x, y, z
+
+
+def calculate_rpy(mask, rgb_img):
+ rect = cv2.minAreaRect(max(cv2.findContours(mask.astype(np.uint8), cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE)[0], key=cv2.contourArea))
+ box = cv2.boxPoints(rect)
+
+ len1 = np.linalg.norm(box[1] - box[0])
+ len2 = np.linalg.norm(box[1] - box[2])
+ if len1 >= len2:
+ vec = box[1] - box[0]
+ else:
+ vec = box[1] - box[2]
+
+ if vec[0] < 0:
+ vec = -vec
+
+ angle = math.degrees(math.atan2(vec[1], vec[0]))
+ if angle <= -90.0:
+ angle += 180
+
+ y = angle/180.0 * math.pi
+ p = 0.0
+ r = 0.0
+ return r, p, y
+
+
+def draw_box(set_confidence, rgb_img, boxes, confidences, class_ids, labels):
+ for i, box in enumerate(boxes):
+ if confidences[i] < set_confidence:
+ continue
+ else:
+ x_center, y_center, width, height = box[:4]
+
+ p1 = [int((x_center - width / 2)), int((y_center - height / 2))]
+ p2 = [int((x_center + width / 2)), int((y_center + height / 2))]
+ cv2.rectangle(rgb_img, p1, p2, (255, 255, 0), 2)
+
+ cv2.putText(rgb_img, f'{labels[class_ids[i]]}: {confidences[i]*100:.2f}', (p1[0], p1[1] - 10),
+ cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 255, 0), 2)
+
+
+def draw_mask(set_confidence, rgb_img, masks, confidences, orig_shape):
+ for i, mask in enumerate(masks):
+ if confidences[i] < set_confidence:
+ continue
+ else:
+ mask = cv2.resize(mask.astype(np.uint8), orig_shape[::-1], interpolation=cv2.INTER_LINEAR)
+ rgb_img[mask > 0] = rgb_img[mask > 0] * 0.5 + np.array([0, 0, 255]) * 0.5
+
+
class DetectNode(Node):
def __init__(self, name):
super().__init__(name)
- self.depth_image = None
- self.fx = self.fy = self.cx = self.cy = None
+ self.device = None
self.checkpoint_path = None
+ self.checkpoint_name = None
+ self.function = None
+ self.output_boxes = None
+ self.output_masks = None
+ self.camera_info = []
+ self.camera_size = []
+
+ '''Init'''
self._init_param()
self._init_model()
+ self._init_publisher()
self._init_subscriber()
self.cv_bridge = CvBridge()
- self.pub_pose_list = self.create_publisher(PointWithIDArray, '/pose/cv_detect_pose', 10)
- if self.output_detect_image:
- self.pub_detect_image = self.create_publisher(Image, '/image/detect_image', 10)
def _init_param(self):
pkg_dir = os.path.dirname(detect_part.__file__)
- self.declare_parameter('checkpoint_name', 'yolo11s.pt')
- checkpoint_name = self.get_parameter('checkpoint_name').value
- self.checkpoint_path = os.path.join(pkg_dir, 'checkpoint', checkpoint_name)
+ self.declare_parameter('checkpoint_name', 'yolo11s-seg.pt')
+ self.checkpoint_name = self.get_parameter('checkpoint_name').value
+ self.checkpoint_path = os.path.join(pkg_dir, 'checkpoint', self.checkpoint_name)
- self.declare_parameter('output_detect_image', False)
- self.output_detect_image = self.get_parameter('output_detect_image').value
+ self.declare_parameter('output_boxes', True)
+ self.output_boxes = self.get_parameter('output_boxes').value
- self.declare_parameter('set_confidence', 0.6)
+ self.declare_parameter('output_masks', False)
+ self.output_masks = self.get_parameter('output_masks').value
+
+ self.declare_parameter('set_confidence', 0.5)
self.set_confidence = self.get_parameter('set_confidence').value
def _init_model(self):
- device = torch.device('cuda' if torch.cuda.is_available() else 'cpu')
+ self.device = torch.device('cuda' if torch.cuda.is_available() else 'cpu')
try:
- self.model = YOLO(self.checkpoint_path).to(device)
+ self.model = YOLO(self.checkpoint_path).to(self.device)
except Exception as e:
self.get_logger().error(f'Failed to load YOLO model: {e}')
raise
self.get_logger().info(f'Loading checkpoint from: {self.checkpoint_path}')
+ if self.checkpoint_name.endswith('-seg.pt'):
+ self.function = self._seg_image
+ elif self.checkpoint_name.endswith('.pt'):
+ self.function = self._detect_image
+ else:
+ self.function = None
+ self.get_logger().error(f'Unknown checkpoint: {self.checkpoint_name}')
+
+ def _init_publisher(self):
+ self.pub_pose_list = self.create_publisher(PoseWithIDArray, '/pose/cv_detect_pose', 10)
+
+ if self.output_boxes or self.output_masks:
+ self.pub_detect_image = self.create_publisher(Image, '/image/detect_image', 10)
+
def _init_subscriber(self):
self.sub_camera_info = self.create_subscription(
CameraInfo,
- '/camera/color/camera_info',
+ '/camera # x = depth_img[v, u] / 1e3/color/camera_info',
self._camera_info_callback,
10
)
- # sync get color and depth img
+ '''Sync get color and depth img'''
self.sub_color_image = Subscriber(self, Image, '/camera/color/image_raw')
self.sub_depth_image = Subscriber(self, Image, '/camera/depth/image_raw')
@@ -80,47 +214,51 @@ class DetectNode(Node):
self.sync_subscriber.registerCallback(self._sync_callback)
def _sync_callback(self, color_img_ros, depth_img_ros):
- if None in (self.fx, self.fy, self.cx, self.cy):
+ if not self.camera_info:
self.get_logger().warn('Camera intrinsics not yet received. Waiting...')
return
color_img_cv = self.cv_bridge.imgmsg_to_cv2(color_img_ros, "bgr8")
depth_img_cv = self.cv_bridge.imgmsg_to_cv2(depth_img_ros, '16UC1')
- # self.get_logger().info(f'Color image: {color_img_cv.shape}')
- # self.get_logger().info(f'Depth image: {depth_img_cv.shape}')
- if self.output_detect_image:
- detect_img, pose_dict = self._detect_image(color_img_cv, depth_img_cv)
- self.pub_detect_image.publish(detect_img)
+ if self.output_boxes:
+ img, pose_dict = self.function(color_img_cv, depth_img_cv)
+ self.pub_detect_image.publish(img)
else:
- pose_dict = self._detect_image(color_img_cv)
+ pose_dict = self.function(color_img_cv, depth_img_cv)
- pose_list_all = PointWithIDArray()
- for (class_id, class_name), points in pose_dict.items():
+ pose_list_all = PoseWithIDArray()
+ for (class_id, class_name), pose_list in pose_dict.items():
pose_list_all.objects.append(
- PointWithID(
+ PoseWithID(
class_name = class_name,
class_id = class_id,
- points = points
+ pose_list = pose_list
)
)
self.pub_pose_list.publish(pose_list_all)
+ '''Get camera info'''
def _camera_info_callback(self, msg: CameraInfo):
- self.fx = msg.k[0]
- self.fy = msg.k[4]
- self.cx = msg.k[2]
- self.cy = msg.k[5]
+ self.camera_size.append(msg.width)
+ self.camera_size.append(msg.height)
+
+ self.camera_info.append(msg.k[2])
+ self.camera_info.append(msg.k[5])
+ self.camera_info.append(msg.k[0])
+ self.camera_info.append(msg.k[4])
+
self.destroy_subscription(self.sub_camera_info)
+ '''Use detection model'''
def _detect_image(self, rgb_img: np.ndarray, depth_img: np.ndarray):
pose_dict = defaultdict(list)
img_h, img_w = rgb_img.shape[:2]
- border_x = img_w * 0.12
- border_y = img_h * 0.10
+ border_x = img_w * 0.10
+ border_y = img_h * 0.08
results = self.model(rgb_img)
result = results[0]
@@ -140,97 +278,82 @@ class DetectNode(Node):
# self.get_logger().info(f'Skipping object near edge at ({x_center},{y_center})')
continue
- x, y, z = self._calculate_coordinate(depth_img, x_center, y_center, width, height)
+ x, y, z = calculate_coordinate(self, depth_img, self.camera_info, x_center, y_center, width, height)
if (x, y, z) != (0.0, 0.0, 0.0):
+ pose = Pose()
+ pose.position = Point(x=x, y=y, z=z)
+ pose.orientation = Quaternion(x=0, y=0, z=0)
pose_dict[int(class_ids[i]), labels[class_ids[i]]].append(Point(x=x, y=y, z=z))
- if self.output_detect_image:
- self._draw_box(rgb_img, boxes, confidences, class_ids, labels)
+ if self.output_boxes:
+ draw_box(self.set_confidence, rgb_img, boxes, confidences, class_ids, labels)
return self.cv_bridge.cv2_to_imgmsg(rgb_img, "bgr8"), pose_dict
else:
return pose_dict
- def _draw_box(self, rgb_img, boxes, confidences, class_ids, labels):
- for i, box in enumerate(boxes):
+ '''Use segmentation model'''
+ def _seg_image(self, rgb_img: np.ndarray, depth_img: np.ndarray):
+
+ pose_dict = defaultdict(list)
+
+
+ '''Define border'''
+ border_x, border_y = rgb_img.shape[:2][0] * 0.10, rgb_img.shape[:2][1] * 0.08
+
+ '''Get Predict Results'''
+ results = self.model(rgb_img)
+ result = results[0]
+
+ '''Get masks'''
+ masks = result.masks.data.cpu().numpy()
+ orig_shape = result.masks.orig_shape
+
+ '''Get boxes'''
+ boxes = result.boxes.xywh.cpu().numpy()
+ confidences = result.boxes.conf.cpu().numpy()
+ class_ids = result.boxes.cls.cpu().numpy()
+ labels = result.names
+
+
+ for i, (mask, box) in enumerate(zip(masks, boxes)):
+ '''Confidence Filter'''
if confidences[i] < self.set_confidence:
continue
else:
x_center, y_center, width, height = box[:4]
- p1 = [int((x_center - width / 2)), int((y_center - height / 2))]
- p2 = [int((x_center + width / 2)), int((y_center + height / 2))]
- cv2.rectangle(rgb_img, p1, p2, (255, 255, 0), 2)
+ '''Border Filter'''
+ if not (border_x <= x_center <= rgb_img.shape[:2][1] - border_x
+ and border_y <= y_center <= rgb_img.shape[:2][0] - border_y):
+ # self.get_logger().info(f'Skipping object near edge at ({x_center},{y_center})')
+ continue
- cv2.putText(rgb_img, f'{labels[class_ids[i]]}: {confidences[i]*100:.2f}', (p1[0], p1[1] - 10),
- cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 255, 0), 2)
- # cv2.putText(rgb_img, f'cs:{x:.2f} {y:.2f} {z:.2f}', (p1[0], p1[1] - 35),
- # cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 255, 0), 2)
+ mask = cv2.resize(mask, orig_shape[::-1], cv2.INTER_LINEAR)
+ rgb_masked = rgb_img.copy()
+ rgb_masked[mask == 0] = 0
- def _calculate_coordinate(self, depth_img: np.ndarray, u, v, width: int, height: int) -> tuple[float, float, float]:
- u = int(round(u))
- v = int(round(v))
+ roll, pitch, yaw = calculate_rpy(mask, rgb_img)
- if not (0 <= v < depth_img.shape[0] and 0 <= u < depth_img.shape[1]):
- self.get_logger().warning(f'Calculate coordinate error: u={u}, v={v}')
- return 0.0, 0.0, 0.0
-
- window_size = 39
- half = window_size // 2
-
- patch = depth_img[max(0, v - half):v + half + 1, max(0, u - half):u + half + 1:2].flatten()
- valid_depths = patch[patch > 0]
-
- if len(valid_depths) == 0:
- patch = self._get_nine_patch_samples(depth_img, u, v, width, height)
- valid_depths = patch[patch > 0]
-
- if len(valid_depths) == 0:
- self.get_logger().warning(f'No valid depth in window at ({u}, {v})')
- return 0.0, 0.0, 0.0
-
- valid_depths = self.iqr(valid_depths)
-
- # x = depth_img[v, u] / 1e3
- depth = np.median(valid_depths) / 1e3
- x = depth
-
- y = -(u - self.cx) * x / self.fx
- z = -(v - self.cy) * x / self.fy
-
- return x, y, z
-
- def _get_nine_patch_samples(self, depth_img, u, v, width, height):
- ws = [int(round(random.uniform(-0.05*width, 0.05*width)-width/4)), 0, int(round(random.uniform(-0.05*width, 0.05*width)+width/4))]
- hs = [int(round(random.uniform(-0.05*height, 0.05*height)-height/4)), 0, int(round(random.uniform(-0.05*height, 0.05*height)+height/4))]
-
- window_size = 25
- half = window_size // 2
-
- patch = []
- for w in ws:
- for h in hs:
- patch.append(
- depth_img[int(max(0, v + h - half)):int(min(v + h + half + 1, depth_img.shape[0])):2,
- int(max(0, u + w - half)):int(min(u + w + half + 1, depth_img.shape[1])):2].flatten())
-
- return np.concatenate(patch)
-
- def iqr(self, depths, threshold: float = 1.5):
- if len(depths) < 7:
- return depths
-
- q1 = np.percentile(depths, 25)
- q3 = np.percentile(depths, 75)
-
- iqr = q3 - q1
-
- lower_bound = q1 - iqr * threshold
- upper_bound = q3 + iqr * threshold
-
- iqr_depths = depths[(depths >= lower_bound) & (depths <= upper_bound)]
-
- return iqr_depths
+ x, y, z = calculate_coordinate(self, depth_img, self.camera_info, x_center, y_center, width, height)
+ if (x, y, z) != (0.0, 0.0, 0.0):
+ pose = Pose()
+ pose.position = Point(x=x, y=y, z=z)
+ pose.orientation = Quaternion(x=roll, y=pitch, z=yaw)
+ pose_dict[int(class_ids[i]), labels[class_ids[i]]].append(pose)
+ '''mask_img and box_img is or not output'''
+ if self.output_boxes and self.output_masks:
+ draw_box(self.set_confidence, rgb_img, boxes, confidences, class_ids, labels)
+ draw_mask(self.set_confidence, rgb_img, masks, confidences, orig_shape)
+ return self.cv_bridge.cv2_to_imgmsg(rgb_img, "bgr8"), pose_dict
+ elif self.output_boxes and not self.output_masks:
+ draw_box(self.set_confidence, rgb_img, boxes, confidences, class_ids, labels)
+ return self.cv_bridge.cv2_to_imgmsg(rgb_img, "bgr8"), pose_dict
+ elif not self.output_boxes and self.output_masks:
+ draw_mask(self.set_confidence, rgb_img, masks, confidences, orig_shape)
+ return self.cv_bridge.cv2_to_imgmsg(rgb_img, "bgr8"), pose_dict
+ else:
+ return pose_dict
def main(args=None):
@@ -247,3 +370,4 @@ def main(args=None):
if __name__ == '__main__':
main()
+
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/sub_pose.py b/HiveCoreR0/src/robot_vision/detect_part/detect_part/sub_pose.py
index 9fc9dfb..31213a6 100644
--- a/HiveCoreR0/src/robot_vision/detect_part/detect_part/sub_pose.py
+++ b/HiveCoreR0/src/robot_vision/detect_part/detect_part/sub_pose.py
@@ -1,20 +1,20 @@
import rclpy
from rclpy.node import Node
-from interfaces.msg import PointWithIDArray
+from interfaces.msg import PoseWithIDArray
class SubPose(Node):
def __init__(self, name):
super().__init__(name)
- self.sub = self.create_subscription(PointWithIDArray, '/pose/cv_detect_pose', self.pose_callback, 10)
+ self.sub = self.create_subscription(PoseWithIDArray, '/pose/cv_detect_pose', self.pose_callback, 10)
def pose_callback(self, msg):
pose_dict = {}
for object in msg.objects:
pose_dict[object.class_id] = {
'name' : object.class_name,
- 'points' : object.points,
+ 'pose_list' : object.pose_list,
}
self.get_logger().info(f'{pose_dict}')
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/cfg/__pycache__/__init__.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/cfg/__pycache__/__init__.cpython-310.pyc
index c2f244f..dea8faf 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/cfg/__pycache__/__init__.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/cfg/__pycache__/__init__.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/exporter.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/exporter.cpython-310.pyc
index 30b12bc..5bf6f4d 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/exporter.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/exporter.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/model.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/model.cpython-310.pyc
index 4e3ebb5..75fbbd3 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/model.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/model.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/predictor.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/predictor.cpython-310.pyc
index 42e3a0b..6c13f92 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/predictor.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/predictor.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/results.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/results.cpython-310.pyc
index 60cd80c..b9de1aa 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/results.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/results.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/trainer.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/trainer.cpython-310.pyc
index 17dde2a..bd470b6 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/trainer.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/trainer.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/validator.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/validator.cpython-310.pyc
index 33242b1..4c6044d 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/validator.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/engine/__pycache__/validator.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/__pycache__/model.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/__pycache__/model.cpython-310.pyc
index 6016335..2d295f1 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/__pycache__/model.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/__pycache__/model.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/predict.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/predict.cpython-310.pyc
index 205f276..5c3e365 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/predict.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/predict.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/train.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/train.cpython-310.pyc
index d5df816..d7aa796 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/train.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/train.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/val.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/val.cpython-310.pyc
index cf14a9d..b1392f1 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/val.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/detect/__pycache__/val.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/predict.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/predict.cpython-310.pyc
index de88088..83eb604 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/predict.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/predict.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/train.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/train.cpython-310.pyc
index 7a4374f..7eb80b3 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/train.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/train.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/val.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/val.cpython-310.pyc
index 551c3be..1af0725 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/val.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/models/yolo/segment/__pycache__/val.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/__pycache__/autobackend.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/__pycache__/autobackend.cpython-310.pyc
index 0b18d56..1b5fa9f 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/__pycache__/autobackend.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/__pycache__/autobackend.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/__pycache__/tasks.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/__pycache__/tasks.cpython-310.pyc
index 02a248f..daa6d09 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/__pycache__/tasks.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/__pycache__/tasks.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/tasks.py b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/tasks.py
index 1d32b81..be21d18 100644
--- a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/tasks.py
+++ b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/nn/tasks.py
@@ -1456,7 +1456,7 @@ def torch_safe_load(weight, safe_only=False):
f"with https://github.com/ultralytics/yolov5.\nThis model is NOT forwards compatible with "
f"YOLOv8 at https://github.com/ultralytics/ultralytics."
f"\nRecommend fixes are to train a new model using the latest 'ultralytics' package or to "
- f"run a command with an official Ultralytics model, i.e. 'yolo predict model=yolo11n.pt'"
+ f"run a command with an official Ultralytics model, i.e. 'yolo predict model=yolo11n.det.pt'"
)
) from e
elif e.name == "numpy._core":
@@ -1469,7 +1469,7 @@ def torch_safe_load(weight, safe_only=False):
f"{weight} appears to require '{e.name}', which is not in Ultralytics requirements."
f"\nAutoInstall will run now for '{e.name}' but this feature will be removed in the future."
f"\nRecommend fixes are to train a new model using the latest 'ultralytics' package or to "
- f"run a command with an official Ultralytics model, i.e. 'yolo predict model=yolo11n.pt'"
+ f"run a command with an official Ultralytics model, i.e. 'yolo predict model=yolo11n.det.pt'"
)
check_requirements(e.name) # install missing module
ckpt = torch_load(file, map_location="cpu")
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/__init__.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/__init__.cpython-310.pyc
index 6642e0e..82d7305 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/__init__.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/__init__.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/checks.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/checks.cpython-310.pyc
index e513e5b..f1fca4f 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/checks.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/checks.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/downloads.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/downloads.cpython-310.pyc
index 9215214..f3f87f5 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/downloads.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/downloads.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/files.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/files.cpython-310.pyc
index cf32451..52c349b 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/files.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/files.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/loss.cpython-310.pyc b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/loss.cpython-310.pyc
index c8e632e..73e36a2 100644
Binary files a/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/loss.cpython-310.pyc and b/HiveCoreR0/src/robot_vision/detect_part/detect_part/ultralytics/utils/__pycache__/loss.cpython-310.pyc differ
diff --git a/HiveCoreR0/src/robot_vision/detect_part/launch/camera_detect.launch.py b/HiveCoreR0/src/robot_vision/detect_part/launch/camera_detect.launch.py
index 71c1c5b..3d8dd80 100644
--- a/HiveCoreR0/src/robot_vision/detect_part/launch/camera_detect.launch.py
+++ b/HiveCoreR0/src/robot_vision/detect_part/launch/camera_detect.launch.py
@@ -51,8 +51,9 @@ def load_parameters(context, args):
def generate_launch_description():
args_detect = [
- DeclareLaunchArgument('checkpoint_name', default_value='yolo11s.pt'),
- DeclareLaunchArgument('output_detect_image', default_value='True'),
+ DeclareLaunchArgument('checkpoint_name', default_value='yolo11s-seg.pt'),
+ DeclareLaunchArgument('output_boxes', default_value='True'),
+ DeclareLaunchArgument('output_masks', default_value='False'),
DeclareLaunchArgument('set_confidence', default_value='0.6'),
]
@@ -311,7 +312,8 @@ def generate_launch_description():
def create_detect_node(context):
checkpoint = LaunchConfiguration('checkpoint_name').perform(context)
- output = LaunchConfiguration('output_detect_image').perform(context)
+ output_boxes = LaunchConfiguration('output_boxes').perform(context)
+ output_masks = LaunchConfiguration('output_masks').perform(context)
conf = LaunchConfiguration('set_confidence').perform(context)
return [
@@ -320,7 +322,8 @@ def generate_launch_description():
executable='detect_node',
parameters=[{
'checkpoint_name': checkpoint,
- 'output_detect_image': output.lower() == 'true',
+ 'output_boxes': output_boxes.lower() == 'true',
+ 'output_masks': output_masks.lower() == 'true',
'set_confidence': float(conf)
}]
)
diff --git a/HiveCoreR0/src/robot_vision/interfaces/CMakeLists.txt b/HiveCoreR0/src/robot_vision/interfaces/CMakeLists.txt
index 0189259..14bf212 100644
--- a/HiveCoreR0/src/robot_vision/interfaces/CMakeLists.txt
+++ b/HiveCoreR0/src/robot_vision/interfaces/CMakeLists.txt
@@ -14,8 +14,8 @@ find_package(geometry_msgs REQUIRED)
# find_package( REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
- "msg/PointWithID.msg"
- "msg/PointWithIDArray.msg"
+ "msg/PoseWithID.msg"
+ "msg/PoseWithIDArray.msg"
DEPENDENCIES geometry_msgs
)
diff --git a/HiveCoreR0/src/robot_vision/interfaces/msg/PointWithIDArray.msg b/HiveCoreR0/src/robot_vision/interfaces/msg/PointWithIDArray.msg
deleted file mode 100644
index 5dec81a..0000000
--- a/HiveCoreR0/src/robot_vision/interfaces/msg/PointWithIDArray.msg
+++ /dev/null
@@ -1 +0,0 @@
-PointWithID[] objects
diff --git a/HiveCoreR0/src/robot_vision/interfaces/msg/PointWithID.msg b/HiveCoreR0/src/robot_vision/interfaces/msg/PoseWithID.msg
similarity index 52%
rename from HiveCoreR0/src/robot_vision/interfaces/msg/PointWithID.msg
rename to HiveCoreR0/src/robot_vision/interfaces/msg/PoseWithID.msg
index ac830f3..7bd2373 100644
--- a/HiveCoreR0/src/robot_vision/interfaces/msg/PointWithID.msg
+++ b/HiveCoreR0/src/robot_vision/interfaces/msg/PoseWithID.msg
@@ -1,4 +1,4 @@
string class_name
int32 class_id
-geometry_msgs/Point[] points
+geometry_msgs/Pose[] pose_list
diff --git a/HiveCoreR0/src/robot_vision/interfaces/msg/PoseWithIDArray.msg b/HiveCoreR0/src/robot_vision/interfaces/msg/PoseWithIDArray.msg
new file mode 100644
index 0000000..3400899
--- /dev/null
+++ b/HiveCoreR0/src/robot_vision/interfaces/msg/PoseWithIDArray.msg
@@ -0,0 +1 @@
+PoseWithID[] objects