|
11 | 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
12 | 12 | # See the License for the specific language governing permissions and |
13 | 13 | # limitations under the License. |
| 14 | +import time |
14 | 15 | from typing import List, Literal, Optional, cast |
15 | 16 |
|
16 | 17 | import numpy as np |
@@ -46,6 +47,77 @@ def depth_to_point_cloud( |
46 | 47 | return points.astype(np.float32, copy=False) |
47 | 48 |
|
48 | 49 |
|
| 50 | +def _publish_gripping_point_debug_data( |
| 51 | + connector: ROS2Connector, |
| 52 | + obj_points_xyz: NDArray[np.float32], |
| 53 | + gripping_points_xyz: list[NDArray[np.float32]], |
| 54 | + base_frame_id: str = "egoarm_base_link", |
| 55 | + publish_duration: float = 10.0, |
| 56 | +) -> None: |
| 57 | + """Publish the gripping point debug data for visualization in RVIZ via point cloud and marker array. |
| 58 | +
|
| 59 | + Args: |
| 60 | + connector: The ROS2 connector. |
| 61 | + obj_points_xyz: The list of objects found in the image. |
| 62 | + gripping_points_xyz: The list of gripping points in the base frame. |
| 63 | + base_frame_id: The base frame id. |
| 64 | + publish_duration: Duration in seconds to publish the data (default: 10.0). |
| 65 | + """ |
| 66 | + |
| 67 | + from geometry_msgs.msg import Point, Point32, Pose, Vector3 |
| 68 | + from sensor_msgs.msg import PointCloud |
| 69 | + from std_msgs.msg import Header |
| 70 | + from visualization_msgs.msg import Marker, MarkerArray |
| 71 | + |
| 72 | + points = ( |
| 73 | + np.concatenate(obj_points_xyz, axis=0) |
| 74 | + if obj_points_xyz |
| 75 | + else np.zeros((0, 3), dtype=np.float32) |
| 76 | + ) |
| 77 | + |
| 78 | + msg = PointCloud() # type: ignore[reportUnknownArgumentType] |
| 79 | + msg.header.frame_id = base_frame_id # type: ignore[reportUnknownMemberType] |
| 80 | + msg.points = [Point32(x=float(p[0]), y=float(p[1]), z=float(p[2])) for p in points] # type: ignore[reportUnknownArgumentType] |
| 81 | + pub = connector.node.create_publisher( # type: ignore[reportUnknownMemberType] |
| 82 | + PointCloud, "/debug_gripping_points_pointcloud", 10 |
| 83 | + ) |
| 84 | + |
| 85 | + marker_pub = connector.node.create_publisher( # type: ignore[reportUnknownMemberType] |
| 86 | + MarkerArray, "/debug_gripping_points_markerarray", 10 |
| 87 | + ) |
| 88 | + marker_array = MarkerArray() |
| 89 | + header = Header() |
| 90 | + header.frame_id = base_frame_id |
| 91 | + header.stamp = connector.node.get_clock().now().to_msg() |
| 92 | + markers = [] |
| 93 | + for i, p in enumerate(gripping_points_xyz): |
| 94 | + m = Marker() |
| 95 | + m.header = header |
| 96 | + m.type = Marker.SPHERE |
| 97 | + m.action = Marker.ADD |
| 98 | + m.pose = Pose(position=Point(x=float(p[0]), y=float(p[1]), z=float(p[2]))) |
| 99 | + m.scale = Vector3(x=0.04, y=0.04, z=0.04) |
| 100 | + m.id = i |
| 101 | + m.color.r = 1.0 # type: ignore[reportUnknownMemberType] |
| 102 | + m.color.g = 0.0 # type: ignore[reportUnknownMemberType] |
| 103 | + m.color.b = 0.0 # type: ignore[reportUnknownMemberType] |
| 104 | + m.color.a = 1.0 # type: ignore[reportUnknownMemberType] |
| 105 | + |
| 106 | + # m.ns = str(i) |
| 107 | + |
| 108 | + markers.append(m) # type: ignore[reportUnknownArgumentType] |
| 109 | + marker_array.markers = markers |
| 110 | + |
| 111 | + start_time = time.time() |
| 112 | + publish_rate = 10.0 # Hz |
| 113 | + sleep_duration = 1.0 / publish_rate |
| 114 | + |
| 115 | + while time.time() - start_time < publish_duration: |
| 116 | + marker_pub.publish(marker_array) |
| 117 | + pub.publish(msg) |
| 118 | + time.sleep(sleep_duration) |
| 119 | + |
| 120 | + |
49 | 121 | class PointCloudFromSegmentation: |
50 | 122 | """Generate a masked point cloud for an object and transform it to a target frame. |
51 | 123 |
|
@@ -511,96 +583,3 @@ def run( |
511 | 583 | f = pts |
512 | 584 | filtered.append(f.astype(np.float32, copy=False)) |
513 | 585 | return filtered |
514 | | - |
515 | | - |
516 | | -import time |
517 | | - |
518 | | -from rai.communication.ros2 import ROS2Context |
519 | | - |
520 | | -ROS2Context() |
521 | | - |
522 | | - |
523 | | -def main(): |
524 | | - from rai.communication.ros2.connectors import ROS2Connector |
525 | | - |
526 | | - connector = ROS2Connector() |
527 | | - connector.node.declare_parameter("conversion_ratio", 1.0) |
528 | | - time.sleep(5) |
529 | | - est = GrippingPointEstimator( |
530 | | - strategy="biggest_plane", ransac_iterations=400, distance_threshold_m=0.008 |
531 | | - ) |
532 | | - |
533 | | - pc_gen = PointCloudFromSegmentation( |
534 | | - connector=connector, |
535 | | - camera_topic="/rgbd_camera/camera_image_color", |
536 | | - depth_topic="/rgbd_camera/camera_image_depth", |
537 | | - camera_info_topic="/rgbd_camera/camera_info", |
538 | | - source_frame="egofront_rgbd_camera_depth_optical_frame", |
539 | | - target_frame="egoarm_base_link", |
540 | | - ) |
541 | | - points_xyz = pc_gen.run( |
542 | | - object_name="box" |
543 | | - ) # ndarray of shape (N, 3) in target frame |
544 | | - print(points_xyz) |
545 | | - filt = PointCloudFilter(strategy="dbscan", dbscan_eps=0.02, dbscan_min_samples=10) |
546 | | - points_xyz = filt.run(points_xyz) # same list shape, each np.float32 (N,3) |
547 | | - grip_points = est.run(points_xyz) |
548 | | - |
549 | | - print(grip_points) |
550 | | - from geometry_msgs.msg import Point32 |
551 | | - from sensor_msgs.msg import PointCloud |
552 | | - |
553 | | - points = ( |
554 | | - np.concatenate(points_xyz, axis=0) |
555 | | - if points_xyz |
556 | | - else np.zeros((0, 3), dtype=np.float32) |
557 | | - ) |
558 | | - |
559 | | - msg = PointCloud() # type: ignore[reportUnknownArgumentType] |
560 | | - msg.header.frame_id = "egoarm_base_link" # type: ignore[reportUnknownMemberType] |
561 | | - msg.points = [Point32(x=float(p[0]), y=float(p[1]), z=float(p[2])) for p in points] # type: ignore[reportUnknownArgumentType] |
562 | | - pub = connector.node.create_publisher( # type: ignore[reportUnknownMemberType] |
563 | | - PointCloud, "/debug/get_grabbing_point_pointcloud", 10 |
564 | | - ) |
565 | | - from geometry_msgs.msg import Point, Pose, Vector3 |
566 | | - from std_msgs.msg import Header |
567 | | - from visualization_msgs.msg import Marker, MarkerArray |
568 | | - |
569 | | - marker_pub = connector.node.create_publisher( # type: ignore[reportUnknownMemberType] |
570 | | - MarkerArray, "/debug/get_grabbing_point_marker_array", 10 |
571 | | - ) |
572 | | - marker_array = MarkerArray() |
573 | | - header = Header() |
574 | | - header.frame_id = "egoarm_base_link" |
575 | | - # header.stamp = connector.node.get_clock().now().to_msg() |
576 | | - markers = [] |
577 | | - for i, p in enumerate(grip_points): |
578 | | - m = Marker() |
579 | | - m.header = header |
580 | | - m.type = Marker.SPHERE |
581 | | - m.action = Marker.ADD |
582 | | - m.pose = Pose(position=Point(x=float(p[0]), y=float(p[1]), z=float(p[2]))) |
583 | | - m.scale = Vector3(x=0.04, y=0.04, z=0.04) |
584 | | - m.id = i |
585 | | - m.color.r = 1.0 # type: ignore[reportUnknownMemberType] |
586 | | - m.color.g = 0.0 # type: ignore[reportUnknownMemberType] |
587 | | - m.color.b = 0.0 # type: ignore[reportUnknownMemberType] |
588 | | - m.color.a = 1.0 # type: ignore[reportUnknownMemberType] |
589 | | - |
590 | | - # m.ns = str(i) |
591 | | - |
592 | | - markers.append(m) # type: ignore[reportUnknownArgumentType] |
593 | | - marker_array.markers = markers |
594 | | - |
595 | | - while True: |
596 | | - connector.node.get_logger().info( # type: ignore[reportUnknownMemberType] |
597 | | - f"publishing pointcloud to /debug/get_grabbing_point_pointcloud: {len(msg.points)} points, mean: {np.array(points.mean(axis=0))}." |
598 | | - ) |
599 | | - |
600 | | - marker_pub.publish(marker_array) |
601 | | - pub.publish(msg) |
602 | | - time.sleep(0.1) |
603 | | - |
604 | | - |
605 | | -if __name__ == "__main__": |
606 | | - main() |
0 commit comments