Skip to content

Commit cbc1211

Browse files
author
Benteng Ma
committed
Reformated files
1 parent 4669b72 commit cbc1211

File tree

4 files changed

+70
-58
lines changed

4 files changed

+70
-58
lines changed

.gitignore

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -137,4 +137,7 @@ legacy/choosing_wait_position/src/choosing_wait_position/final_lift_key_point/mo
137137

138138
# Python extension setup files
139139
.pylintrc
140-
mypy.ini
140+
mypy.ini
141+
142+
# Pycharm extension setup files
143+
.idea/*

common/vision/lasr_vision_feature_extraction/src/lasr_vision_feature_extraction/__init__.py

Lines changed: 26 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,13 @@
1+
import json
2+
from os import path
3+
4+
import cv2
5+
import numpy as np
6+
import rospkg
7+
import torch
8+
import torch.nn as nn
9+
import torch.nn.functional as F
10+
import torchvision.models as models
111
from lasr_vision_feature_extraction.categories_and_attributes import (
212
CategoriesAndAttributes,
313
CelebAMaskHQCategoriesAndAttributes,
@@ -9,16 +19,6 @@
919
ImageOfCloth,
1020
)
1121

12-
import numpy as np
13-
import cv2
14-
import torch
15-
import rospkg
16-
from os import path
17-
import torch.nn as nn
18-
import torch.nn.functional as F
19-
import torchvision.models as models
20-
import json
21-
2222

2323
def X2conv(in_channels, out_channels, inner_channels=None):
2424
inner_channels = out_channels // 2 if inner_channels is None else inner_channels
@@ -150,7 +150,7 @@ def forward(self, x):
150150

151151
class CombinedModel(nn.Module):
152152
def __init__(
153-
self, segment_model: nn.Module, predict_model: nn.Module, cat_layers: int = None
153+
self, segment_model: nn.Module, predict_model: nn.Module, cat_layers: int = None
154154
):
155155
super(CombinedModel, self).__init__()
156156
self.segment_model = segment_model
@@ -162,7 +162,7 @@ def forward(self, x: torch.Tensor):
162162
seg_masks = self.segment_model(x)
163163
seg_masks_ = seg_masks.detach()
164164
if self.cat_layers:
165-
seg_masks_ = seg_masks_[:, 0 : self.cat_layers]
165+
seg_masks_ = seg_masks_[:, 0: self.cat_layers]
166166
x = torch.cat((x, seg_masks_), dim=1)
167167
else:
168168
x = torch.cat((x, seg_masks_), dim=1)
@@ -313,10 +313,10 @@ def forward(self, x):
313313

314314
class Predictor:
315315
def __init__(
316-
self,
317-
model: torch.nn.Module,
318-
device: torch.device,
319-
categories_and_attributes: CategoriesAndAttributes,
316+
self,
317+
model: torch.nn.Module,
318+
device: torch.device,
319+
categories_and_attributes: CategoriesAndAttributes,
320320
):
321321
self.model = model
322322
self.device = device
@@ -325,7 +325,7 @@ def __init__(
325325
self._thresholds_mask: list[float] = []
326326
self._thresholds_pred: list[float] = []
327327
for key in sorted(
328-
list(self.categories_and_attributes.merged_categories.keys())
328+
list(self.categories_and_attributes.merged_categories.keys())
329329
):
330330
self._thresholds_mask.append(
331331
self.categories_and_attributes.thresholds_mask[key]
@@ -339,7 +339,7 @@ def __init__(
339339
def predict(self, rgb_image: np.ndarray) -> ImageWithMasksAndAttributes:
340340
mean_val = np.mean(rgb_image)
341341
image_tensor = (
342-
torch.from_numpy(rgb_image).permute(2, 0, 1).unsqueeze(0).float() / 255.0
342+
torch.from_numpy(rgb_image).permute(2, 0, 1).unsqueeze(0).float() / 255.0
343343
)
344344
pred_masks, pred_classes = self.model(image_tensor)
345345
# Apply binary erosion and dilation to the masks
@@ -373,9 +373,9 @@ def load_face_classifier_model():
373373
cat_layers = CelebAMaskHQCategoriesAndAttributes.merged_categories.keys().__len__()
374374
segment_model = UNetWithResnetEncoder(num_classes=cat_layers)
375375
predictions = (
376-
len(CelebAMaskHQCategoriesAndAttributes.attributes)
377-
- len(CelebAMaskHQCategoriesAndAttributes.avoided_attributes)
378-
+ len(CelebAMaskHQCategoriesAndAttributes.mask_labels)
376+
len(CelebAMaskHQCategoriesAndAttributes.attributes)
377+
- len(CelebAMaskHQCategoriesAndAttributes.avoided_attributes)
378+
+ len(CelebAMaskHQCategoriesAndAttributes.mask_labels)
379379
)
380380
predict_model = MultiLabelResNet(
381381
num_labels=predictions, input_channels=cat_layers + 3
@@ -394,6 +394,7 @@ def load_face_classifier_model():
394394
)
395395
return model
396396

397+
397398
def load_cloth_classidifer_model():
398399
num_classes = len(DeepFashion2GeneralizedCategoriesAndAttributes.attributes)
399400
model = SegmentPredictorBbox(num_masks=num_classes + 4, num_labels=num_classes + 4, num_bbox_classes=4)
@@ -410,6 +411,7 @@ def load_cloth_classidifer_model():
410411
)
411412
return model
412413

414+
413415
def pad_image_to_even_dims(image):
414416
# Get the current shape of the image
415417
height, width, _ = image.shape
@@ -456,13 +458,13 @@ def extract_mask_region(frame, mask, expand_x=0.5, expand_y=0.5):
456458
new_w = min(frame.shape[1] - x, new_w)
457459
new_h = min(frame.shape[0] - y, new_h)
458460

459-
face_region = frame[y : y + int(new_h), x : x + int(new_w)]
461+
face_region = frame[y: y + int(new_h), x: x + int(new_w)]
460462
return face_region
461463
return None
462464

463465

464466
def predict_frame(
465-
head_frame, torso_frame, full_frame, head_mask, torso_mask, head_predictor, cloth_predictor,
467+
head_frame, torso_frame, full_frame, head_mask, torso_mask, head_predictor, cloth_predictor,
466468
):
467469
full_frame = cv2.cvtColor(full_frame, cv2.COLOR_BGR2RGB)
468470
head_frame = cv2.cvtColor(head_frame, cv2.COLOR_BGR2RGB)
@@ -499,7 +501,7 @@ def load_torch_model(model, optimizer, path="model.pth", cpu_only=False):
499501

500502

501503
def binary_erosion_dilation(
502-
tensor, thresholds, erosion_iterations=1, dilation_iterations=1
504+
tensor, thresholds, erosion_iterations=1, dilation_iterations=1
503505
):
504506
"""
505507
Apply binary threshold, followed by erosion and dilation to a tensor.

common/vision/lasr_vision_feature_extraction/src/lasr_vision_feature_extraction/categories_and_attributes.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -190,7 +190,7 @@ class DeepFashion2GeneralizedCategoriesAndAttributes(CategoriesAndAttributes):
190190
for key in mask_categories:
191191
if key not in _categories_to_merge:
192192
merged_categories[key] = [key]
193-
mask_labels = ['top', 'down', 'outwear', 'dress',]
193+
mask_labels = ['top', 'down', 'outwear', 'dress', ]
194194
selective_attributes = {}
195195
plane_attributes = []
196196
avoided_attributes = []

common/vision/lasr_vision_feature_extraction/src/lasr_vision_feature_extraction/image_with_masks_and_attributes.py

Lines changed: 39 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -17,16 +17,16 @@ def _softmax(x: list[float]) -> list[float]:
1717

1818
def _exp(x):
1919
"""Compute e^x for a given x. A simple implementation of the exponential function."""
20-
return 2.718281828459045**x # Using an approximation of Euler's number e
20+
return 2.718281828459045 ** x # Using an approximation of Euler's number e
2121

2222

2323
class ImageWithMasksAndAttributes:
2424
def __init__(
25-
self,
26-
image: np.ndarray,
27-
masks: dict[str, np.ndarray],
28-
attributes: dict[str, float],
29-
categories_and_attributes: CategoriesAndAttributes,
25+
self,
26+
image: np.ndarray,
27+
masks: dict[str, np.ndarray],
28+
attributes: dict[str, float],
29+
categories_and_attributes: CategoriesAndAttributes,
3030
):
3131
self.image: np.ndarray = image
3232
self.masks: dict[str, np.ndarray] = masks
@@ -41,7 +41,7 @@ def __init__(
4141

4242
self.selective_attribute_dict: dict[str, dict[str, float]] = {}
4343
for category in sorted(
44-
list(self.categories_and_attributes.selective_attributes.keys())
44+
list(self.categories_and_attributes.selective_attributes.keys())
4545
):
4646
self.selective_attribute_dict[category] = {}
4747
temp_list: list[float] = []
@@ -51,7 +51,7 @@ def __init__(
5151
temp_list.append(self.attributes[attribute])
5252
softmax_list = _softmax(temp_list)
5353
for i, attribute in enumerate(
54-
self.categories_and_attributes.selective_attributes[category]
54+
self.categories_and_attributes.selective_attributes[category]
5555
):
5656
self.selective_attribute_dict[category][attribute] = softmax_list[i]
5757

@@ -67,17 +67,17 @@ def _max_value_tuple(some_dict: dict[str, float]) -> tuple[str, float]:
6767

6868
class ImageOfPerson(ImageWithMasksAndAttributes):
6969
def __init__(
70-
self,
71-
image: np.ndarray,
72-
masks: dict[str, np.ndarray],
73-
attributes: dict[str, float],
74-
categories_and_attributes: CategoriesAndAttributes,
70+
self,
71+
image: np.ndarray,
72+
masks: dict[str, np.ndarray],
73+
attributes: dict[str, float],
74+
categories_and_attributes: CategoriesAndAttributes,
7575
):
7676
super().__init__(image, masks, attributes, categories_and_attributes)
7777

7878
@classmethod
7979
def from_parent_instance(
80-
cls, parent_instance: ImageWithMasksAndAttributes
80+
cls, parent_instance: ImageWithMasksAndAttributes
8181
) -> "ImageOfPerson":
8282
"""
8383
Creates an instance of ImageOfPerson using the properties of an
@@ -156,7 +156,7 @@ def describe(self) -> str:
156156
hair_colour_str = "gray"
157157

158158
if (
159-
male
159+
male
160160
): # here 'male' is only used to determine whether it is confident to decide whether the person has beard
161161
if not facial_hair[0] == "No_Beard":
162162
description += "and has beard. "
@@ -180,7 +180,7 @@ def describe(self) -> str:
180180
if necktie[0]:
181181
wearables.append("a necktie")
182182
description += (
183-
", ".join(wearables[:-2] + [" and ".join(wearables[-2:])]) + ". "
183+
", ".join(wearables[:-2] + [" and ".join(wearables[-2:])]) + ". "
184184
)
185185

186186
if description == "This customer has ":
@@ -209,17 +209,17 @@ def describe(self) -> str:
209209

210210
class ImageOfCloth(ImageWithMasksAndAttributes):
211211
def __init__(
212-
self,
213-
image: np.ndarray,
214-
masks: dict[str, np.ndarray],
215-
attributes: dict[str, float],
216-
categories_and_attributes: CategoriesAndAttributes,
212+
self,
213+
image: np.ndarray,
214+
masks: dict[str, np.ndarray],
215+
attributes: dict[str, float],
216+
categories_and_attributes: CategoriesAndAttributes,
217217
):
218218
super().__init__(image, masks, attributes, categories_and_attributes)
219219

220220
@classmethod
221221
def from_parent_instance(
222-
cls, parent_instance: ImageWithMasksAndAttributes
222+
cls, parent_instance: ImageWithMasksAndAttributes
223223
) -> "ImageOfCloth":
224224
"""
225225
Creates an instance of ImageOfCloth using the properties of an
@@ -240,24 +240,31 @@ def describe(self) -> str:
240240
"down": self.attributes["down"] > self.categories_and_attributes.thresholds_pred["down"],
241241
"outwear": self.attributes["outwear"] > self.categories_and_attributes.thresholds_pred["outwear"],
242242
"dress": self.attributes["dress"] > self.categories_and_attributes.thresholds_pred["dress"],
243-
244-
"short sleeve top": self.attributes["short sleeve top"] > self.categories_and_attributes.thresholds_pred["short sleeve top"],
245-
"long sleeve top": self.attributes["long sleeve top"] > self.categories_and_attributes.thresholds_pred["long sleeve top"],
246-
"short sleeve outwear": self.attributes["short sleeve outwear"] > self.categories_and_attributes.thresholds_pred["short sleeve outwear"],
247-
"long sleeve outwear": self.attributes["long sleeve outwear"] > self.categories_and_attributes.thresholds_pred["long sleeve outwear"],
243+
244+
"short sleeve top": self.attributes["short sleeve top"] >
245+
self.categories_and_attributes.thresholds_pred["short sleeve top"],
246+
"long sleeve top": self.attributes["long sleeve top"] > self.categories_and_attributes.thresholds_pred[
247+
"long sleeve top"],
248+
"short sleeve outwear": self.attributes["short sleeve outwear"] >
249+
self.categories_and_attributes.thresholds_pred["short sleeve outwear"],
250+
"long sleeve outwear": self.attributes["long sleeve outwear"] >
251+
self.categories_and_attributes.thresholds_pred["long sleeve outwear"],
248252
"vest": self.attributes["vest"] > self.categories_and_attributes.thresholds_pred["vest"],
249253
"sling": self.attributes["sling"] > self.categories_and_attributes.thresholds_pred["sling"],
250254
"outwear": self.attributes["outwear"] > self.categories_and_attributes.thresholds_pred["outwear"],
251255
"shorts": self.attributes["shorts"] > self.categories_and_attributes.thresholds_pred["shorts"],
252256
"trousers": self.attributes["trousers"] > self.categories_and_attributes.thresholds_pred["trousers"],
253257
"skirt": self.attributes["skirt"] > self.categories_and_attributes.thresholds_pred["skirt"],
254-
"short sleeve dress": self.attributes["short sleeve dress"] > self.categories_and_attributes.thresholds_pred["short sleeve dress"],
255-
"long sleeve dress": self.attributes["long sleeve dress"] > self.categories_and_attributes.thresholds_pred["long sleeve dress"],
256-
"vest dress": self.attributes["vest dress"] > self.categories_and_attributes.thresholds_pred["vest dress"],
257-
"sling dress": self.attributes["sling dress"] > self.categories_and_attributes.thresholds_pred["sling dress"],
258+
"short sleeve dress": self.attributes["short sleeve dress"] >
259+
self.categories_and_attributes.thresholds_pred["short sleeve dress"],
260+
"long sleeve dress": self.attributes["long sleeve dress"] >
261+
self.categories_and_attributes.thresholds_pred["long sleeve dress"],
262+
"vest dress": self.attributes["vest dress"] > self.categories_and_attributes.thresholds_pred[
263+
"vest dress"],
264+
"sling dress": self.attributes["sling dress"] > self.categories_and_attributes.thresholds_pred[
265+
"sling dress"],
258266
},
259267
"description": "this descrcription will be completed if we find out it is better to do it here.",
260268
}
261269

262270
return result
263-

0 commit comments

Comments
 (0)