Skip to content

Commit afea560

Browse files
Yadunundvaheta
andauthored
Update tester to send request with images filled (#10)
* loading images * load camera params * Fill images Signed-off-by: Yadunund <[email protected]> * Get tester working without photoneo Signed-off-by: Yadunund <[email protected]> --------- Signed-off-by: Yadunund <[email protected]> Co-authored-by: Vahe <[email protected]>
1 parent 007535b commit afea560

File tree

1 file changed

+88
-6
lines changed

1 file changed

+88
-6
lines changed

ibpc_tester/ibpc_tester/ibpc_tester.py

Lines changed: 88 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,14 @@
11
# todo(Yadunund): Add copyright.
22

3-
import sys
3+
import cv2
4+
from cv_bridge import CvBridge
5+
import numpy as np
46
from pathlib import Path
7+
import sys
58

69
import rclpy
710
from rclpy.node import Node
11+
from rclpy.qos import QoSProfile, DurabilityPolicy, ReliabilityPolicy
812

913
from bop_toolkit_lib.config import datasets_path
1014
from bop_toolkit_lib.dataset_params import (
@@ -13,10 +17,75 @@
1317
get_present_scene_ids,
1418
get_split_params,
1519
)
16-
from bop_toolkit_lib.inout import load_json, load_scene_gt, load_scene_camera
20+
from bop_toolkit_lib.inout import load_json, load_scene_gt, load_scene_camera, load_im, load_depth
1721

18-
from ibpc_interfaces.msg import PoseEstimate
22+
from geometry_msgs.msg import Pose as PoseMsg
23+
from ibpc_interfaces.msg import Camera as CameraMsg
24+
from ibpc_interfaces.msg import Photoneo as PhotoneoMsg
25+
from ibpc_interfaces.msg import PoseEstimate as PoseEstimateMsg
1926
from ibpc_interfaces.srv import GetPoseEstimates
27+
from sensor_msgs.msg import Image
28+
29+
from scipy.spatial.transform import Rotation
30+
31+
# Helper functions
32+
def pose_mat_to_ros(rot: np.ndarray, trans: np.ndarray):
33+
r = Rotation.from_matrix(rot)
34+
q = r.as_quat()
35+
msg = PoseMsg()
36+
msg.orientation.x = q[0]
37+
msg.orientation.y = q[1]
38+
msg.orientation.z = q[2]
39+
msg.orientation.w = q[3]
40+
msg.position.x = float(trans[0])
41+
msg.position.y = float(trans[1])
42+
msg.position.z = float(trans[2])
43+
return msg
44+
45+
46+
class BOPCamera:
47+
def __init__(self, path, camera_name, img_id):
48+
self._load_images(path, camera_name, img_id)
49+
self._load_camera_params(path, camera_name, img_id)
50+
51+
def _load_images(self, path, camera_name, img_id):
52+
self.camera_name = camera_name
53+
self.depth = load_depth(f'{path}/depth_{self.camera_name}/{img_id:06d}.png')
54+
if self.camera_name != 'photoneo':
55+
self.rgb = load_im(f'{path}/rgb_{self.camera_name}/{img_id:06d}.png')[:,:,0]
56+
self.aolp = load_im(f'{path}/aolp_{self.camera_name}/{img_id:06d}.png')
57+
self.dolp = load_im(f'{path}/dolp_{self.camera_name}/{img_id:06d}.png')
58+
else:
59+
self.rgb = load_im(f'{path}/rgb_{self.camera_name}/{img_id:06d}.png')
60+
self.aolp = None
61+
self.dolp = None
62+
self.br = CvBridge()
63+
def to_camera_msg(self, node, debug_pub) -> CameraMsg:
64+
msg = CameraMsg()
65+
msg.info.header.frame_id = self.camera_name
66+
# msg.info.header.stamp = node.get_clock().now()
67+
msg.info.k = self.K.reshape(-1)
68+
msg.pose = pose_mat_to_ros(self.R, self.t)
69+
msg.rgb = self.br.cv2_to_imgmsg(self.rgb, "8UC1")
70+
debug_pub.publish(msg.rgb)
71+
msg.depth = self.br.cv2_to_imgmsg(self.depth, "32FC1")
72+
msg.aolp = self.br.cv2_to_imgmsg(self.aolp, "8UC1")
73+
msg.dolp = self.br.cv2_to_imgmsg(self.dolp, "8UC1")
74+
return msg
75+
def to_photoneo_msg(self, node, debug_pub) -> PhotoneoMsg:
76+
msg = PhotoneoMsg()
77+
msg.info.header.frame_id = self.camera_name
78+
# msg.info.header.stamp = node.get_clock().now()
79+
msg.info.k = self.K.reshape(-1)
80+
msg.pose = pose_mat_to_ros(self.R, self.t)
81+
msg.rgb = self.br.cv2_to_imgmsg(self.rgb, "8UC1")
82+
msg.depth = self.br.cv2_to_imgmsg(self.depth, "32FC1")
83+
84+
def _load_camera_params(self, path, camera_name, img_id):
85+
self.camera_params = load_scene_camera(f'{path}/scene_camera_{camera_name}.json')[img_id]
86+
self.K = self.camera_params['cam_K']
87+
self.R = self.camera_params['cam_R_w2c']
88+
self.t = self.camera_params['cam_t_w2c']
2089

2190

2291
def main(argv=sys.argv):
@@ -28,10 +97,18 @@ def main(argv=sys.argv):
2897
node.get_logger().info(f"Datasets path is set to {datasets_path}.")
2998

3099
# Declare parameters.
31-
node.declare_parameter("dataset_name", "lm")
100+
node.declare_parameter("dataset_name", "ipd")
32101
dataset_name = node.get_parameter("dataset_name").get_parameter_value().string_value
33102
node.get_logger().info("Loading from dataset {dataset_name}.")
34103

104+
# Debug parameters.
105+
qos_profile = QoSProfile(
106+
depth=10, # Queue size (adjust as needed)
107+
durability=DurabilityPolicy.TRANSIENT_LOCAL,
108+
reliability=ReliabilityPolicy.RELIABLE # or RELIABLE, depending on your needs
109+
)
110+
debug_pub = node.create_publisher(Image, "/ibpc_tester_debug_images", qos_profile)
111+
35112
# Load the test split.
36113
test_split = get_split_params(datasets_path, dataset_name, "test")
37114
node.get_logger().info(f"Parsed test split: {test_split}")
@@ -48,10 +125,13 @@ def main(argv=sys.argv):
48125
scene_dir = Path(test_split["split_path"]) / "{scene_id:06d}".format(
49126
scene_id=scene_id
50127
)
51-
scene_gt = load_scene_gt(test_split["scene_gt_tpath"].format(scene_id=scene_id))
128+
scene_gt = load_scene_gt(test_split["scene_gt_rgb_photoneo_tpath"].format(scene_id=scene_id))
52129
for img_id, obj_gts in scene_gt.items():
53130
request = GetPoseEstimates.Request()
54-
# todo(Yadunund): Fill in cameras and cv.
131+
request.cameras.append(BOPCamera(scene_dir, 'cam1', img_id).to_camera_msg(node, debug_pub))
132+
request.cameras.append(BOPCamera(scene_dir, 'cam2', img_id).to_camera_msg(node, debug_pub))
133+
request.cameras.append(BOPCamera(scene_dir, 'cam3', img_id).to_camera_msg(node, debug_pub))
134+
# request.photoneo = BOPCamera(scene_dir, 'photoneo', img_id).to_photoneo_msg(node)
55135
# todo(Yadunund): Load corresponding rgb, depth and polarized image for this img_id.
56136
for obj_gt in obj_gts:
57137
request.object_ids.append(int(obj_gt["obj_id"]))
@@ -66,6 +146,8 @@ def main(argv=sys.argv):
66146
node.get_logger().error(
67147
"Exception while calling service: %r" % future.exception()
68148
)
149+
# todo(Yadunund): Remove break after dataset is fixed.
150+
break
69151

70152
node.destroy_node()
71153
rclpy.try_shutdown()

0 commit comments

Comments
 (0)