|
4 | 4 |
|
5 | 5 | from sensor_msgs.msg import Image, CameraInfo |
6 | 6 | from std_msgs.msg import Header |
7 | | - |
| 7 | +import cv2 |
8 | 8 | from cv_bridge import CvBridge |
9 | 9 | import numpy as np |
10 | 10 |
|
@@ -44,20 +44,36 @@ def publish_dummy_data(self): |
44 | 44 | header.stamp = now |
45 | 45 | header.frame_id = 'camera_link' |
46 | 46 |
|
47 | | - rgb_image = np.random.randint( |
48 | | - 0, 255, (480, 640, 3), dtype=np.uint8 |
49 | | - ) |
| 47 | + # Create a simple scene with geometric shapes at different depths |
| 48 | + rgb_image = np.zeros((480, 640, 3), dtype=np.uint8) |
| 49 | + depth_image = np.full((480, 640), 3000, dtype=np.uint16) # Background at 3000mm |
| 50 | + |
| 51 | + # Add a large rectangle (closer object) - like a wall or box |
| 52 | + cv2.rectangle(rgb_image, (150, 120), (490, 360), (100, 150, 200), -1) # Filled rectangle |
| 53 | + cv2.rectangle(depth_image, (150, 120), (490, 360), 1200, -1) # 1200mm depth |
| 54 | + |
| 55 | + # Add a smaller circle (closest object) - like a ball |
| 56 | + cv2.circle(rgb_image, (320, 240), 80, (50, 200, 50), -1) # Green circle |
| 57 | + cv2.circle(depth_image, (320, 240), 80, 800, -1) # 800mm depth (closest) |
| 58 | + |
| 59 | + # Add another rectangle (medium distance) |
| 60 | + cv2.rectangle(rgb_image, (50, 300), (200, 450), (200, 100, 100), -1) # Reddish rectangle |
| 61 | + cv2.rectangle(depth_image, (50, 300), (200, 450), 1800, -1) # 1800mm depth |
| 62 | + |
| 63 | + # Optional: Add some gradient/texture to make it more realistic |
| 64 | + noise = np.random.randint(-20, 20, rgb_image.shape, dtype=np.int16) |
| 65 | + rgb_image = np.clip(rgb_image.astype(np.int16) + noise, 0, 255).astype(np.uint8) |
| 66 | + |
| 67 | + # Add slight depth variation (noise) |
| 68 | + depth_noise = np.random.randint(-30, 30, depth_image.shape, dtype=np.int16) |
| 69 | + depth_image = np.clip(depth_image.astype(np.int32) + depth_noise, 0, 65535).astype(np.uint16) |
50 | 70 |
|
51 | 71 | rgb_msg = self.bridge.cv2_to_imgmsg( |
52 | 72 | rgb_image, encoding='bgr8' |
53 | 73 | ) |
54 | 74 | rgb_msg.header = header |
55 | 75 | self.rgb_pub.publish(rgb_msg) |
56 | 76 |
|
57 | | - depth_image = np.full( |
58 | | - (480, 640), 1500, dtype=np.uint16 |
59 | | - ) |
60 | | - |
61 | 77 | depth_msg = self.bridge.cv2_to_imgmsg( |
62 | 78 | depth_image, encoding='mono16' |
63 | 79 | ) |
|
0 commit comments