-
Notifications
You must be signed in to change notification settings - Fork 12
/
Copy pathscenegraph.py
892 lines (786 loc) · 38.2 KB
/
scenegraph.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
import base64
import math
import os
from collections import Counter
from io import BytesIO
from pathlib import Path, PosixPath
import cv2
import numpy as np
import omegaconf
import supervision as sv
import torch
import ollama
from omegaconf import DictConfig
from PIL import Image
from sklearn.cluster import DBSCAN
from segment_anything import SamAutomaticMaskGenerator, SamPredictor, sam_model_registry
from GroundingDINO.groundingdino.datasets import transforms as T
from utils.utils_scenegraph.mapping import compute_spatial_similarities, merge_detections_to_objects
from utils.utils_scenegraph.slam_classes import MapObjectList
from utils.utils_scenegraph.utils import filter_objects, gobs_to_detection_list, text2value
from utils.utils_scenegraph.grounded_sam_demo import get_grounding_output, load_image, load_model
ADDITIONAL_PSL_OPTIONS = {
'log4j.threshold': 'INFO'
}
ADDITIONAL_CLI_OPTIONS = [
# '--postgres'
]
class RoomNode():
def __init__(self, caption):
self.caption = caption
self.exploration_level = 0
self.nodes = set()
self.group_nodes = []
class GroupNode():
def __init__(self, caption=''):
self.caption = caption
self.exploration_level = 0
self.corr_score = 0
self.center = None
self.center_node = None
self.nodes = []
self.edges = set()
def __lt__(self, other):
return self.corr_score < other.corr_score
def get_graph(self):
self.center = np.array([node.center for node in self.nodes]).mean(axis=0)
min_distance = np.inf
for node in self.nodes:
distance = np.linalg.norm(np.array(node.center) - np.array(self.center))
if distance < min_distance:
min_distance = distance
self.center_node = node
self.edges.update(node.edges)
self.caption = self.graph_to_text(self.nodes, self.edges)
def graph_to_text(self, nodes, edges):
nodes_text = ', '.join([node.caption for node in nodes])
edges_text = ', '.join([f"{edge.node1.caption} {edge.relation} {edge.node2.caption}" for edge in edges])
return f"Nodes: {nodes_text}. Edges: {edges_text}."
class ObjectNode():
def __init__(self):
self.is_new_node = True
self.is_goal_node = False
self.caption = None
self.object = None
self.reason = None
self.center = None
self.room_node = None
self.exploration_level = 0
self.distance = 2
self.score = 0.5
self.edges = set()
def __lt__(self, other):
return self.score < other.score
def add_edge(self, edge):
self.edges.add(edge)
def remove_edge(self, edge):
self.edges.discard(edge)
def set_caption(self, new_caption):
for edge in list(self.edges):
edge.delete()
self.is_new_node = True
self.caption = new_caption
self.reason = None
self.distance = 2
self.score = 0.5
self.exploration_level = 0
self.edges.clear()
def set_object(self, object):
self.object = object
self.object['node'] = self
def set_center(self, center):
self.center = center
class Edge():
def __init__(self, node1, node2):
self.node1 = node1
self.node2 = node2
node1.add_edge(self)
node2.add_edge(self)
self.relation = None
def set_relation(self, relation):
self.relation = relation
def delete(self):
self.node1.remove_edge(self)
self.node2.remove_edge(self)
def text(self):
text = '({}, {}, {})'.format(self.node1.caption, self.node2.caption, self.relation)
return text
class SceneGraph():
def __init__(self, map_resolution, map_size_cm, map_size, camera_matrix, is_navigation=True, agent=None) -> None:
self.map_resolution = map_resolution
self.map_size_cm = map_size_cm
self.map_size = map_size
full_w, full_h = self.map_size, self.map_size
self.full_w = full_w
self.full_h = full_h
self.visited = torch.zeros(full_w, full_h).float().cpu().numpy()
self.num_of_goal = torch.zeros(full_w, full_h).int()
self.camera_matrix = camera_matrix
self.SAM_ENCODER_VERSION = "vit_h"
self.sam_variant = 'groundedsam'
self.device = 'cuda'
self.classes = ['item']
self.BG_CLASSES = ["wall", "floor", "ceiling"]
self.rooms = ['bedroom', 'living room', 'bathroom', 'kitchen', 'dining room', 'office room', 'gym', 'lounge', 'laundry room']
self.objects = MapObjectList(device=self.device)
self.objects_post = MapObjectList(device=self.device)
self.nodes = []
self.edge_text = ''
self.edge_list = []
self.group_nodes = []
self.init_room_nodes()
self.reason_visualization = ''
self.is_navigation = is_navigation
self.llm_name = 'llama3.2-vision'
self.vlm_name = 'llama3.2-vision'
self.seg_xyxy = None
self.seg_caption = None
self.groundingdino_config_file = 'GroundingDINO/groundingdino/config/GroundingDINO_SwinT_OGC.py'
self.groundingdino_checkpoint = 'data/models/groundingdino_swint_ogc.pth'
self.sam_version = 'vit_h'
self.sam_checkpoint = 'data/models/sam_vit_h_4b8939.pth'
self.segment2d_results = []
self.max_detections_per_object = 10
self.threshold_list = {'bathtub': 2, 'bed': 7, 'cabinet': 3, 'chair': 5, 'chest_of_drawers': 5, 'clothes': 9, 'counter': 4, 'cushion': 7, 'fireplace': 4, 'gym_equipment': 7, 'picture': 9, 'plant': 3, 'seating': 2, 'shower': 2, 'sink': 3, 'sofa': 9, 'stool': 5, 'table': 8, 'toilet': 3, 'towel': 4, 'tv_monitor': 2, 'treadmill. fitness equipment.': 0}
self.small_objects = ['bathtub', 'chest_of_drawers', 'cushion', 'plant', 'seating', 'shower', 'toilet', 'tv_monitor']
self.found_goal_times_threshold = 1
self.N_max = 10
self.node_space = 'bathtub. bed. cabinet. chair. drawers. clothes. counter. cushion. fireplace. gym. picture. plant. seating. shower. sink. sofa. stool. table. toilet. towel. tv. treadmill. fitness equipment.'
self.prompt_edge_proposal = '''
Provide the most possible single spatial relationship for each of the following object pairs. Answer with only one relationship per pair, and separate each answer with a newline character. Do not response superfluous text.
Example 1:
Input:
Object pair(s):
(cabinet, chair)
Output:
next to
Example 2:
Input:
Object pair(s):
(table, lamp)
(bed, nightstand)
Output:
on
next to
Now input is:
Object pair(s):
'''
self.prompt_relation = 'What is the spatial relationship between the {} and the {} in the image? You can only answer a word or phrase that describes a spatial relationship.'
self.prompt_discriminate_relation = 'In the image, do {} and {} satisfy the relationship of {}? Only answer "yes" or "no".'
self.prompt_room_predict = 'Which room is the most likely to have the [{}] in: [{}]. Only answer the room.'
self.prompt_graph_corr_0 = 'What is the probability of A and B appearing together. [A:{}], [B:{}]. Even if you do not have enough information, you have to answer with a value from 0 to 1 anyway. Answer only the value of probability and do not answer any other text.'
self.prompt_graph_corr_1 = 'What else do you need to know to determine the probability of A and B appearing together? [A:{}], [B:{}]. Please output a short question (output only one sentence with no additional text).'
self.prompt_graph_corr_2 = 'Here is the objects and relationships near A: [{}] You answer the following question with a short sentence based on this information. Question: {}'
self.prompt_graph_corr_3 = 'The probability of A and B appearing together is about {}. Based on the dialog: [{}], re-determine the probability of A and B appearing together. A:[{}], B:[{}]. Even if you do not have enough information, you have to answer with a value from 0 to 1 anyway. Answer only the value of probability and do not answer any other text.'
self.mask_generator = self.get_sam_mask_generator(self.sam_variant, self.device)
self.set_cfg()
self.set_agent(agent)
def reset(self):
full_w, full_h = self.map_size, self.map_size
self.full_w = full_w
self.full_h = full_h
self.visited = torch.zeros(full_w, full_h).float().cpu().numpy()
self.num_of_goal = torch.zeros(full_w, full_h).int()
self.segment2d_results = []
self.reason = ''
self.objects = MapObjectList(device=self.device)
self.objects_post = MapObjectList(device=self.device)
self.nodes = []
self.group_nodes = []
self.init_room_nodes()
self.edge_text = ''
self.edge_list = []
self.reason_visualization = ''
def set_cfg(self):
cfg = {'dataset_config': PosixPath('tools/replica.yaml'), 'scene_id': 'room0', 'start': 0, 'end': -1, 'stride': 5, 'image_height': 680, 'image_width': 1200, 'gsa_variant': 'none', 'detection_folder_name': 'gsa_detections_${gsa_variant}', 'det_vis_folder_name': 'gsa_vis_${gsa_variant}', 'color_file_name': 'gsa_classes_${gsa_variant}', 'device': 'cuda', 'use_iou': True, 'spatial_sim_type': 'overlap', 'phys_bias': 0.0, 'match_method': 'sim_sum', 'semantic_threshold': 0.5, 'physical_threshold': 0.5, 'sim_threshold': 1.2, 'use_contain_number': False, 'contain_area_thresh': 0.95, 'contain_mismatch_penalty': 0.5, 'mask_area_threshold': 25, 'mask_conf_threshold': 0.95, 'max_bbox_area_ratio': 0.5, 'skip_bg': True, 'min_points_threshold': 16, 'downsample_voxel_size': 0.025, 'dbscan_remove_noise': True, 'dbscan_eps': 0.1, 'dbscan_min_points': 10, 'obj_min_points': 0, 'obj_min_detections': 3, 'merge_overlap_thresh': 0.7, 'merge_visual_sim_thresh': 0.8, 'merge_text_sim_thresh': 0.8, 'denoise_interval': 20, 'filter_interval': -1, 'merge_interval': 20, 'save_pcd': True, 'save_suffix': 'overlap_maskconf0.95_simsum1.2_dbscan.1_merge20_masksub', 'vis_render': False, 'debug_render': False, 'class_agnostic': True, 'save_objects_all_frames': True, 'render_camera_path': 'replica_room0.json', 'max_num_points': 512}
cfg = DictConfig(cfg)
if self.is_navigation:
cfg.sim_threshold = 0.8
cfg.sim_threshold_spatial = 0.01
self.cfg = cfg
def set_agent(self, agent):
self.agent = agent
def set_obj_goal(self, obj_goal, obj_goal_sg):
self.obj_goal = obj_goal
self.obj_goal_sg = obj_goal_sg
if self.obj_goal in self.threshold_list:
self.cfg.obj_min_detections = self.threshold_list[self.obj_goal]
def set_navigate_steps(self, navigate_steps):
self.navigate_steps = navigate_steps
def set_room_map(self, room_map):
self.room_map = room_map
def set_fbe_free_map(self, fbe_free_map):
self.fbe_free_map = fbe_free_map
def set_observations(self, observations):
self.observations = observations
self.image_rgb = observations['rgb'].copy()
self.image_depth = observations['depth'].copy()
self.pose_matrix = self.get_pose_matrix()
def set_frontier_map(self, frontier_map):
self.frontier_map = frontier_map
def set_full_map(self, full_map):
self.full_map = full_map
def set_fbe_free_map(self, fbe_free_map):
self.fbe_free_map = fbe_free_map
def set_full_pose(self, full_pose):
self.full_pose = full_pose
def get_nodes(self):
return self.nodes
def get_edges(self):
edges = set()
for node in self.nodes:
edges.update(node.edges)
edges = list(edges)
return edges
def get_seg_xyxy(self):
return self.seg_xyxy
def get_seg_caption(self):
return self.seg_caption
def init_room_nodes(self):
room_nodes = []
for caption in self.rooms:
room_node = RoomNode(caption)
room_nodes.append(room_node)
self.room_nodes = room_nodes
def get_sam_mask_generator(self, variant:str, device) -> SamAutomaticMaskGenerator:
if variant == "sam":
sam = sam_model_registry[self.SAM_ENCODER_VERSION](checkpoint=self.sam_checkpoint)
sam.to(device)
mask_generator = SamAutomaticMaskGenerator(
model=sam,
points_per_side=12,
points_per_batch=144,
pred_iou_thresh=0.88,
stability_score_thresh=0.95,
crop_n_layers=0,
min_mask_region_area=100,
)
return mask_generator
elif variant == "fastsam":
raise NotImplementedError
# from ultralytics import YOLO
# from FastSAM.tools import *
# FASTSAM_CHECKPOINT_PATH = os.path.join(GSA_PATH, "./EfficientSAM/FastSAM-x.pt")
# model = YOLO(args.model_path)
# return model
elif variant == "groundedsam":
model = load_model(self.groundingdino_config_file, self.groundingdino_checkpoint, None, device=device)
predictor = SamPredictor(sam_model_registry[self.sam_version](checkpoint=self.sam_checkpoint).to(device))
return model, predictor
else:
raise NotImplementedError
def get_sam_segmentation_dense(
self, variant:str, model, image: np.ndarray
) -> tuple:
'''
The SAM based on automatic mask generation, without bbox prompting
Args:
model: The mask generator or the YOLO model
image: )H, W, 3), in RGB color space, in range [0, 255]
Returns:
mask: (N, H, W)
xyxy: (N, 4)
conf: (N,)
'''
if variant == "sam":
results = model.generate(image) # type(results) == list
mask = []
xyxy = []
conf = []
for r in results: # type(r) == dict
mask.append(r["segmentation"]) # type(r["segmentation"]) == np.ndarray, r["segmentation"] == [480, 640]
r_xyxy = r["bbox"].copy() # type(r["bbox"]) == list, [x, y, h, w]
# Convert from xyhw format to xyxy format
r_xyxy[2] += r_xyxy[0]
r_xyxy[3] += r_xyxy[1]
xyxy.append(r_xyxy)
conf.append(r["predicted_iou"]) # type(r["predicted_iou"]) == float
mask = np.array(mask)
xyxy = np.array(xyxy)
conf = np.array(conf)
return mask, xyxy, conf
elif variant == "fastsam":
# The arguments are directly copied from the GSA repo
results = model(
image,
imgsz=1024,
device="cuda",
retina_masks=True,
iou=0.9,
conf=0.4,
max_det=100,
)
raise NotImplementedError
elif variant == "groundedsam":
groundingdino = model[0]
sam_predictor = model[1]
transform = T.Compose(
[
T.RandomResize([800], max_size=1333),
T.ToTensor(),
T.Normalize([0.485, 0.456, 0.406], [0.229, 0.224, 0.225]),
]
)
image_resized, _ = transform(Image.fromarray(image), None) # 3, h, w
boxes_filt, caption = get_grounding_output(groundingdino, image_resized, caption=self.node_space, box_threshold=0.3, text_threshold=0.25, with_logits=False, device=self.device)
if len(caption) == 0:
return None, None, None, None
sam_predictor.set_image(image)
# size = image_pil.size
H, W = image.shape[0], image.shape[1]
for i in range(boxes_filt.size(0)):
boxes_filt[i] = boxes_filt[i] * torch.Tensor([W, H, W, H])
boxes_filt[i][:2] -= boxes_filt[i][2:] / 2
boxes_filt[i][2:] += boxes_filt[i][:2]
boxes_filt = boxes_filt.cpu()
transformed_boxes = sam_predictor.transform.apply_boxes_torch(boxes_filt, image.shape[:2]).to(self.device)
mask, conf, _ = sam_predictor.predict_torch(
point_coords = None,
point_labels = None,
boxes = transformed_boxes.to(self.device),
multimask_output = False,
)
mask, xyxy, conf = mask.squeeze(1).cpu().numpy(), boxes_filt.squeeze(1).numpy(), conf.squeeze(1).cpu().numpy()
return mask, xyxy, conf, caption
else:
raise NotImplementedError
def compute_clip_features(self, image, detections, clip_model, clip_preprocess, clip_tokenizer, classes, device):
backup_image = image.copy()
image = Image.fromarray(image)
# padding = args.clip_padding # Adjust the padding amount as needed
padding = 20 # Adjust the padding amount as needed
image_crops = []
image_feats = []
text_feats = []
for idx in range(len(detections.xyxy)):
# Get the crop of the mask with padding
x_min, y_min, x_max, y_max = detections.xyxy[idx]
# Check and adjust padding to avoid going beyond the image borders
image_width, image_height = image.size
left_padding = min(padding, x_min)
top_padding = min(padding, y_min)
right_padding = min(padding, image_width - x_max)
bottom_padding = min(padding, image_height - y_max)
# Apply the adjusted padding
x_min -= left_padding
y_min -= top_padding
x_max += right_padding
y_max += bottom_padding
cropped_image = image.crop((x_min, y_min, x_max, y_max))
# Get the preprocessed image for clip from the crop
preprocessed_image = clip_preprocess(cropped_image).unsqueeze(0).to("cuda")
crop_feat = clip_model.encode_image(preprocessed_image)
crop_feat /= crop_feat.norm(dim=-1, keepdim=True)
class_id = detections.class_id[idx]
tokenized_text = clip_tokenizer([classes[class_id]]).to("cuda")
text_feat = clip_model.encode_text(tokenized_text)
text_feat /= text_feat.norm(dim=-1, keepdim=True)
crop_feat = crop_feat.cpu().numpy()
text_feat = text_feat.cpu().numpy()
image_crops.append(cropped_image)
image_feats.append(crop_feat)
text_feats.append(text_feat)
# turn the list of feats into np matrices
image_feats = np.concatenate(image_feats, axis=0)
text_feats = np.concatenate(text_feats, axis=0)
return image_crops, image_feats, text_feats
def process_cfg(self, cfg: DictConfig):
cfg.dataset_root = Path(cfg.dataset_root)
cfg.dataset_config = Path(cfg.dataset_config)
if cfg.dataset_config.name != "multiscan.yaml":
# For datasets whose depth and RGB have the same resolution
# Set the desired image heights and width from the dataset config
dataset_cfg = omegaconf.OmegaConf.load(cfg.dataset_config)
if cfg.image_height is None:
cfg.image_height = dataset_cfg.camera_params.image_height
if cfg.image_width is None:
cfg.image_width = dataset_cfg.camera_params.image_width
print(f"Setting image height and width to {cfg.image_height} x {cfg.image_width}")
else:
# For dataset whose depth and RGB have different resolutions
assert cfg.image_height is not None and cfg.image_width is not None, \
"For multiscan dataset, image height and width must be specified"
return cfg
def crop_image_and_mask(self, image: Image, mask: np.ndarray, x1: int, y1: int, x2: int, y2: int, padding: int = 0):
""" Crop the image and mask with some padding. I made a single function that crops both the image and the mask at the same time because I was getting shape mismatches when I cropped them separately.This way I can check that they are the same shape."""
image = np.array(image)
# Verify initial dimensions
if image.shape[:2] != mask.shape:
print("Initial shape mismatch: Image shape {} != Mask shape {}".format(image.shape, mask.shape))
return None, None
# Define the cropping coordinates
x1 = max(0, x1 - padding)
y1 = max(0, y1 - padding)
x2 = min(image.shape[1], x2 + padding)
y2 = min(image.shape[0], y2 + padding)
# round the coordinates to integers
x1, y1, x2, y2 = round(x1), round(y1), round(x2), round(y2)
# Crop the image and the mask
image_crop = image[y1:y2, x1:x2]
mask_crop = mask[y1:y2, x1:x2]
# Verify cropped dimensions
if image_crop.shape[:2] != mask_crop.shape:
print("Cropped shape mismatch: Image crop shape {} != Mask crop shape {}".format(image_crop.shape, mask_crop.shape))
return None, None
# convert the image back to a pil image
image_crop = Image.fromarray(image_crop)
return image_crop, mask_crop
def get_pose_matrix(self):
x = self.map_size_cm / 100.0 / 2.0 + self.observations['gps'][0]
y = self.map_size_cm / 100.0 / 2.0 - self.observations['gps'][1]
t = (self.observations['compass'] - np.pi / 2)[0] # input degrees and meters
pose_matrix = np.array([
[np.cos(t), -np.sin(t), 0, x],
[np.sin(t), np.cos(t), 0, y],
[0, 0, 1, 0],
[0, 0, 0, 1],
])
return pose_matrix
def segment2d(self):
if self.sam_variant == 'sam' or self.sam_variant == 'groundedsam':
with torch.no_grad():
mask, xyxy, conf, caption = self.get_sam_segmentation_dense(self.sam_variant, self.mask_generator, self.image_rgb)
self.seg_xyxy = xyxy
self.seg_caption = caption
if caption is None:
return
detections = sv.Detections(
xyxy=xyxy,
confidence=conf,
class_id=np.zeros_like(conf).astype(int),
mask=mask,
)
# with torch.no_grad():
# image_crops, image_feats, text_feats = self.compute_clip_features(image_rgb, detections, self.clip_model, self.clip_preprocess, self.clip_tokenizer, self.classes, self.device)
# image_appear_efficiency = [''] * len(image_crops)
image_appear_efficiency = [''] * len(mask)
self.segment2d_results.append({
"xyxy": detections.xyxy,
"confidence": detections.confidence,
"class_id": detections.class_id,
"mask": detections.mask,
"classes": self.classes,
# "image_crops": image_crops,
# "image_feats": image_feats,
# "text_feats": text_feats,
"image_appear_efficiency": image_appear_efficiency,
"image_rgb": self.image_rgb,
"caption": caption,
})
def mapping3d(self):
depth_array = self.image_depth
depth_array = depth_array[..., 0]
gobs = self.segment2d_results[-1]
cam_K = self.camera_matrix
idx = len(self.segment2d_results) - 1
fg_detection_list, bg_detection_list = gobs_to_detection_list(
cfg = self.cfg,
image = self.image_rgb,
depth_array = depth_array,
cam_K = cam_K,
idx = idx,
gobs = gobs,
trans_pose = self.pose_matrix,
class_names = self.classes,
BG_CLASSES = self.BG_CLASSES,
is_navigation = self.is_navigation
# color_path = color_path,
)
if len(fg_detection_list) == 0:
return
if len(self.objects) == 0:
# Add all detections to the map
for i in range(len(fg_detection_list)):
self.objects.append(fg_detection_list[i])
# Skip the similarity computation
self.objects_post = filter_objects(self.cfg, self.objects)
return
spatial_sim = compute_spatial_similarities(self.cfg, fg_detection_list, self.objects)
# visual_sim = compute_visual_similarities(self.cfg, fg_detection_list, self.objects)
# agg_sim = aggregate_similarities(self.cfg, spatial_sim, visual_sim)
# Threshold sims according to cfg. Set to negative infinity if below threshold
# agg_sim[agg_sim < self.cfg.sim_threshold] = float('-inf')
spatial_sim[spatial_sim < self.cfg.sim_threshold_spatial] = float('-inf')
# self.objects = merge_detections_to_objects(self.cfg, fg_detection_list, self.objects, agg_sim)
self.objects = merge_detections_to_objects(self.cfg, fg_detection_list, self.objects, spatial_sim)
self.objects_post = filter_objects(self.cfg, self.objects)
def get_caption(self):
if self.sam_variant == 'groundedsam':
for idx, object in enumerate(self.objects_post):
caption_list = []
for idx_det in range(len(object["image_idx"])):
caption = self.segment2d_results[object["image_idx"][idx_det]]['caption'][object["mask_idx"][idx_det]]
caption_list = caption_list + caption.split(' ')
caption = self.find_modes(caption_list)[0]
object['captions'] = [caption]
def update_node(self):
# update nodes
for i, node in enumerate(self.nodes):
caption_ori = node.caption
caption_new = node.object['captions'][0]
if caption_ori != caption_new:
node.set_caption(caption_new)
# add new nodes
new_objects = list(filter(lambda object: 'node' not in object, self.objects_post))
for new_object in new_objects:
new_node = ObjectNode()
caption = new_object['captions'][0]
new_node.set_caption(caption)
new_node.set_object(new_object)
self.nodes.append(new_node)
# get node.center and node.room
for node in self.nodes:
points = np.asarray(node.object['pcd'].points)
center = points.mean(axis=0)
x = int(center[0] * 100 / self.map_resolution)
y = int(center[1] * 100 / self.map_resolution)
y = self.map_size - 1 - y
node.set_center([x, y])
if 0 <= x < self.map_size and 0 <= y < self.map_size and hasattr(self, 'room_map'):
if sum(self.room_map[0, :, y, x]!=0).item() == 0:
room_label = 0
else:
room_label = torch.where(self.room_map[0, :, y, x]!=0)[0][0].item()
else:
room_label = 0
if node.room_node is not self.room_nodes[room_label]:
if node.room_node is not None:
node.room_node.nodes.discard(node)
node.room_node = self.room_nodes[room_label]
node.room_node.nodes.add(node)
if node.caption in self.obj_goal_sg:
node.is_goal_node = True
def update_edge(self):
old_nodes = []
new_nodes = []
for i, node in enumerate(self.nodes):
if node.is_new_node:
new_nodes.append(node)
node.is_new_node = False
else:
old_nodes.append(node)
if len(new_nodes) == 0:
return
# create the edge between new_node and old_node
new_edges = []
for i, new_node in enumerate(new_nodes):
for j, old_node in enumerate(old_nodes):
new_edge = Edge(new_node, old_node)
new_edges.append(new_edge)
# create the edge between new_node
for i, new_node1 in enumerate(new_nodes):
for j, new_node2 in enumerate(new_nodes[i + 1:]):
new_edge = Edge(new_node1, new_node2)
new_edges.append(new_edge)
# get all new_edges
new_edges = set()
for i, node in enumerate(self.nodes):
node_new_edges = set(filter(lambda edge: edge.relation is None, node.edges))
new_edges = new_edges | node_new_edges
new_edges = list(new_edges)
for new_edge in new_edges:
image = self.get_joint_image(new_edge.node1, new_edge.node2)
if image is not None:
prompt = self.prompt_relation.format(new_edge.node1.caption, new_edge.node2.caption)
response = self.get_vlm_response(prompt=prompt, image=image)
response = response.replace('.', '').lower()
new_edge.set_relation(response)
new_edges = set()
for i, node in enumerate(self.nodes):
node_new_edges = set(filter(lambda edge: edge.relation is None, node.edges))
new_edges = new_edges | node_new_edges
new_edges = list(new_edges)
# get all relation proposals
if len(new_edges) > 0:
node_pairs = []
for new_edge in new_edges:
node_pairs.append(new_edge.node1.caption)
node_pairs.append(new_edge.node2.caption)
prompt = self.prompt_edge_proposal + '\n({}, {})' * len(new_edges)
prompt = prompt.format(*node_pairs)
relations = self.get_llm_response(prompt=prompt)
relations = relations.split('\n')
if len(relations) == len(new_edges):
for i, relation in enumerate(relations):
new_edges[i].set_relation(relation)
# discriminate all relation proposals
self.free_map = self.fbe_free_map.cpu().numpy()[0,0,::-1].copy() > 0.5
for i, new_edge in enumerate(new_edges):
if new_edge.relation == None or not self.discriminate_relation(new_edge):
new_edge.delete()
def update_group(self):
for room_node in self.room_nodes:
if len(room_node.nodes) > 0:
room_node.group_nodes = []
object_nodes = list(room_node.nodes)
centers = [object_node.center for object_node in object_nodes]
centers = np.array(centers)
dbscan = DBSCAN(eps=10, min_samples=1)
clusters = dbscan.fit_predict(centers)
for i in range(clusters.max() + 1):
group_node = GroupNode()
indices = np.where(clusters == i)[0]
for index in indices:
group_node.nodes.append(object_nodes[index])
group_node.get_graph()
room_node.group_nodes.append(group_node)
def insert_goal(self, goal=None):
if goal is None:
goal = self.obj_goal_sg
self.update_group()
room_node_text = ''
for room_node in self.room_nodes:
if len(room_node.group_nodes) > 0:
room_node_text = room_node_text + room_node.caption + ','
# room_node_text[-2] = '.'
if room_node_text == '':
return None
prompt = self.prompt_room_predict.format(goal, room_node_text)
response = self.get_llm_response(prompt=prompt)
response = response.lower()
predict_room_node = None
for room_node in self.room_nodes:
if len(room_node.group_nodes) > 0 and room_node.caption.lower() in response:
predict_room_node = room_node
if predict_room_node is None:
return None
for group_node in predict_room_node.group_nodes:
corr_score = self.graph_corr(goal, group_node)
group_node.corr_score = corr_score
sorted_group_nodes = sorted(predict_room_node.group_nodes)
self.mid_term_goal = sorted_group_nodes[-1].center
return self.mid_term_goal
def update_scenegraph(self):
print(f'Navigate Step: {self.navigate_steps}', end='\r')
self.segment2d()
if len(self.segment2d_results) > 0:
self.mapping3d()
self.get_caption()
self.update_node()
self.update_edge()
def get_llm_response(self, prompt):
response = ollama.chat(
model=self.llm_name,
messages=[{
'role': 'user',
'content': prompt,
}]
)
return response.message.content
def get_vlm_response(self, prompt, image):
buffered = BytesIO()
image.save(buffered, format='PNG')
image_bytes = base64.b64encode(buffered.getvalue())
image_str = str(image_bytes, 'utf-8')
response = ollama.chat(
model=self.vlm_name,
messages=[{
'role': 'user',
'content': prompt,
'images': [image_str]
}]
)
return response.message.content
def find_modes(self, lst):
if len(lst) == 0:
return ['object']
else:
counts = Counter(lst)
max_count = max(counts.values())
modes = [item for item, count in counts.items() if count == max_count]
return modes
def get_joint_image(self, node1, node2):
image_idx1 = node1.object["image_idx"]
image_idx2 = node2.object["image_idx"]
image_idx = set(image_idx1) & set(image_idx2)
if len(image_idx) == 0:
return None
conf_max = -np.inf
# get joint images of the two nodes
for idx in image_idx:
conf1 = node1.object["conf"][image_idx1.index(idx)]
conf2 = node2.object["conf"][image_idx2.index(idx)]
conf = conf1 + conf2
if conf > conf_max:
conf_max = conf
idx_max = idx
image = self.segment2d_results[idx_max]["image_rgb"]
image = Image.fromarray(image)
return image
def score(self, frontier_locations_16, num_16_frontiers):
scores = np.zeros((num_16_frontiers))
for i, loc in enumerate(frontier_locations_16):
sub_room_map = self.agent.room_map[0,:,max(0,loc[0]-12):min(self.agent.map_size-1,loc[0]+13), max(0,loc[1]-12):min(self.agent.map_size-1,loc[1]+13)].cpu().numpy() # sub_room_map.shape = [9, 25, 25], select the room map around the frontier
whether_near_room = np.max(np.max(sub_room_map, 1),1)
score_1 = np.clip(1-(1-self.agent.prob_array_room)-(1-whether_near_room), 0, 10)
score_2 = 1- np.clip(self.agent.prob_array_room+(1-whether_near_room), -10,1)
scores[i] = np.sum(score_1) - np.sum(score_2)
for i in range(21):
num_obj = len(self.agent.obj_locations[i])
if num_obj <= 0:
continue
frontier_location_mtx = np.tile(frontier_locations_16, (num_obj,1,1))
obj_location_mtx = np.array(self.agent.obj_locations[i])[:,1:]
obj_confidence_mtx = np.tile(np.array(self.agent.obj_locations[i])[:,0],(num_16_frontiers,1)).transpose(1,0)
obj_location_mtx = np.tile(obj_location_mtx, (num_16_frontiers,1,1)).transpose(1,0,2)
dist_frontier_obj = np.square(frontier_location_mtx - obj_location_mtx)
dist_frontier_obj = np.sqrt(np.sum(dist_frontier_obj, axis=2)) / 20
near_frontier_obj = dist_frontier_obj < 1.6
obj_confidence_mtx[near_frontier_obj==False] = 0
obj_confidence_max = np.max(obj_confidence_mtx, axis=0)
score_1 = np.clip(1-(1-self.agent.prob_array_obj[i])-(1-obj_confidence_max), 0, 10)
score_2 = 1- np.clip(self.agent.prob_array_obj[i]+(1-obj_confidence_max), -10,1)
scores += score_1 - score_2
predict_goal_xy = self.insert_goal()
if predict_goal_xy is not None:
predict_goal_xy = np.array(predict_goal_xy).reshape(1, 2)
distance = np.linalg.norm(predict_goal_xy - frontier_locations_16, axis=1)
score = np.tile(1, (num_16_frontiers))
score[distance > 32] = 0
score = score / distance
scores += score
return scores
def discriminate_relation(self, edge):
image = self.get_joint_image(edge.node1, edge.node2)
if image is not None:
response = self.get_vlm_response(self.prompt_discriminate_relation.format(edge.node1.caption, edge.node2.caption, edge.relation), image)
if 'yes' in response.lower():
return True
else:
return False
else:
if edge.node1.room_node != edge.node2.room_node:
return False
x1, y1 = edge.node1.center
x2, y2 = edge.node2.center
distance = math.sqrt((x2 - x1)**2 + (y2 - y1)**2)
if distance > self.map_size // 40:
return False
alpha = math.atan2(y2 - y1, x2 - x1)
sin_2alpha = 2 * math.sin(alpha) * math.cos(alpha)
if not -0.05 < sin_2alpha < 0.05:
return False
n = 3
for i in range(1, n):
x = int(x1 + (x2 - x1) * i / n)
y = int(y1 + (y2 - y1) * i / n)
if not self.free_map[y, x]:
return False
return True
def perception(self):
if not self.agent.found_goal:
self.agent.detect_objects(self.observations)
if self.agent.total_steps % 2 == 0:
room_detection_result = self.agent.glip_demo.inference(self.observations["rgb"][:,:,[2,1,0]], self.agent.rooms_captions)
self.agent.update_room_map(self.observations, room_detection_result)
def graph_corr(self, goal, graph):
prompt = self.prompt_graph_corr_0.format(graph.center_node.caption, goal)
response_0 = self.get_llm_response(prompt=prompt)
prompt = self.prompt_graph_corr_1.format(graph.center_node.caption, goal)
response_1 = self.get_llm_response(prompt=prompt)
prompt = self.prompt_graph_corr_2.format(graph.caption, response_1)
response_2 = self.get_llm_response(prompt=prompt)
prompt = self.prompt_graph_corr_3.format(response_0, response_1 + response_2, graph.center_node.caption, goal)
response_3 = self.get_llm_response(prompt=prompt)
corr_score = text2value(response_3)
return corr_score