Skip to content

Commit

Permalink
Post RoboCup recepionist merge (#264)
Browse files Browse the repository at this point in the history
Co-authored-by: Jared Swift <[email protected]>
Co-authored-by: Siyao <[email protected]>
  • Loading branch information
3 people authored Jul 23, 2024
1 parent dd5f855 commit 64a7495
Show file tree
Hide file tree
Showing 22 changed files with 351 additions and 764 deletions.
1 change: 0 additions & 1 deletion common/helpers/markers/src/markers/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,6 @@ def create_and_publish_marker(
publisher_counts[publisher] += 1
marker_msg = create_marker(point_stamped, idx, r, g, b)
publisher.publish(marker_msg)
rospy.sleep(2) # Needed to prevent markers from being overwritten
if name is not None:
name_location = point_stamped.point
name_location.z += 0.1
Expand Down
17 changes: 0 additions & 17 deletions common/vision/lasr_vision_bodypix/nodes/bodypix_services.py
Original file line number Diff line number Diff line change
Expand Up @@ -117,23 +117,6 @@ def detect_wave(
rospy.logerr(f"Error getting wave point: {e}")
wave_position = PointStamped()

# if debug_publisher is not None:
# cv2_gesture_img = cv2_img.msg_to_cv2_img(request.pcl_msg)
# # Add text to the image
# cv2.putText(
# cv2_gesture_img,
# gesture_to_detect,
# (10, 30),
# cv2.FONT_HERSHEY_SIMPLEX,
# 1,
# (0, 255, 0),
# 2,
# cv2.LINE_AA,
# )
# # Publish the image
# debug_publisher.publish(cv2_img.cv2_img_to_msg(cv2_gesture_img))
# create_and_publish_marker(marker_pub, wave_position, r=0, g=1, b=0)

is_waving = False if gesture_to_detect is None else True

return DetectWaveResponse(
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
#!/usr/bin/env python3
import torch
import rospy
import cv2
import cv2_img
import numpy as np
Expand Down
6 changes: 2 additions & 4 deletions common/vision/lasr_vision_feature_extraction/nodes/service
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@ from lasr_vision_msgs.srv import (
from lasr_vision_feature_extraction.categories_and_attributes import (
CategoriesAndAttributes,
CelebAMaskHQCategoriesAndAttributes,
DeepFashion2GeneralizedCategoriesAndAttributes,
)

from cv2_img import msg_to_cv2_img
Expand Down Expand Up @@ -48,7 +47,8 @@ def detect(
head_frame,
torso_frame,
full_frame,
image_raw=request.image_raw,
head_mask,
torso_mask,
cloth_predictor=cloth_predictor,
)
response = TorchFaceFeatureDetectionDescriptionResponse()
Expand All @@ -58,8 +58,6 @@ def detect(

if __name__ == "__main__":
# predictor will be global when inited, thus will be used within the function above.
# head_model = lasr_vision_feature_extraction.load_face_classifier_model()
# head_predictor = lasr_vision_feature_extraction.Predictor(head_model, torch.device('cpu'), CelebAMaskHQCategoriesAndAttributes)
cloth_model = lasr_vision_feature_extraction.load_cloth_classifier_model()
cloth_predictor = lasr_vision_feature_extraction.ClothPredictor(
cloth_model, torch.device("cpu"), DeepFashion2GeneralizedCategoriesAndAttributes
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,10 @@
import torchvision.models as models
from lasr_vision_feature_extraction.categories_and_attributes import (
CategoriesAndAttributes,
CelebAMaskHQCategoriesAndAttributes,
DeepFashion2GeneralizedCategoriesAndAttributes,
)
from lasr_vision_feature_extraction.image_with_masks_and_attributes import (
ImageWithMasksAndAttributes,
ImageOfPerson,
ImageOfCloth,
)
from lasr_vision_msgs.srv import Vqa, VqaRequest
Expand Down Expand Up @@ -445,32 +443,6 @@ def predict(self, rgb_image: np.ndarray) -> ImageWithMasksAndAttributes:
return image_obj


def load_face_classifier_model():
cat_layers = CelebAMaskHQCategoriesAndAttributes.merged_categories.keys().__len__()
segment_model = UNetWithResnetEncoder(num_classes=cat_layers)
predictions = (
len(CelebAMaskHQCategoriesAndAttributes.attributes)
- len(CelebAMaskHQCategoriesAndAttributes.avoided_attributes)
+ len(CelebAMaskHQCategoriesAndAttributes.mask_labels)
)
predict_model = MultiLabelResNet(
num_labels=predictions, input_channels=cat_layers + 3
)
model = CombinedModel(segment_model, predict_model, cat_layers=cat_layers)
model.eval()

r = rospkg.RosPack()
model, _, _, _ = load_torch_model(
model,
None,
path=path.join(
r.get_path("lasr_vision_feature_extraction"), "models", "face_model.pth"
),
cpu_only=True,
)
return model


def load_cloth_classifier_model():
num_classes = len(DeepFashion2GeneralizedCategoriesAndAttributes.attributes)
model = SegmentPredictorBbox(
Expand Down Expand Up @@ -558,9 +530,6 @@ def predict_frame(
head_frame = pad_image_to_even_dims(head_frame)
torso_frame = pad_image_to_even_dims(torso_frame)

# rst_person = ImageOfPerson.from_parent_instance(
# head_predictor.predict(head_frame)
# ).describe()
rst_cloth = ImageOfCloth.from_parent_instance(
cloth_predictor.predict(torso_frame)
).describe()
Expand Down Expand Up @@ -597,7 +566,6 @@ def predict_frame(
rst_person["hair_shape"] = "long hair"

result = {
**rst_person,
**rst_cloth,
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,166 +10,6 @@ class CategoriesAndAttributes:
thresholds_pred: dict[str, float] = {}


class CelebAMaskHQCategoriesAndAttributes(CategoriesAndAttributes):
mask_categories = [
"cloth",
"r_ear",
"hair",
"l_brow",
"l_eye",
"l_lip",
"mouth",
"neck",
"nose",
"r_brow",
"r_ear",
"r_eye",
"skin",
"u_lip",
"hat",
"l_ear",
"neck_l",
"eye_g",
]
merged_categories = {
"ear": [
"l_ear",
"r_ear",
],
"brow": [
"l_brow",
"r_brow",
],
"eye": [
"l_eye",
"r_eye",
],
"mouth": [
"l_lip",
"u_lip",
"mouth",
],
}
_categories_to_merge = []
for key in sorted(list(merged_categories.keys())):
for cat in merged_categories[key]:
_categories_to_merge.append(cat)
for key in mask_categories:
if key not in _categories_to_merge:
merged_categories[key] = [key]
mask_labels = ["hair"]
selective_attributes = {
"facial_hair": [
"5_o_Clock_Shadow",
"Goatee",
"Mustache",
"No_Beard",
"Sideburns",
],
"hair_colour": [
"Black_Hair",
"Blond_Hair",
"Brown_Hair",
"Gray_Hair",
],
"hair_shape": [
"Straight_Hair",
"Wavy_Hair",
],
}
plane_attributes = [
"Bangs",
"Eyeglasses",
"Wearing_Earrings",
"Wearing_Hat",
"Wearing_Necklace",
"Wearing_Necktie",
"Male",
]
avoided_attributes = [
"Arched_Eyebrows",
"Bags_Under_Eyes",
"Big_Lips",
"Big_Nose",
"Bushy_Eyebrows",
"Chubby",
"Double_Chin",
"High_Cheekbones",
"Narrow_Eyes",
"Oval_Face",
"Pointy_Nose",
"Receding_Hairline",
"Rosy_Cheeks",
"Heavy_Makeup",
"Wearing_Lipstick",
"Attractive",
"Blurry",
"Mouth_Slightly_Open",
"Pale_Skin",
"Smiling",
"Young",
]
attributes = [
"5_o_Clock_Shadow",
"Arched_Eyebrows",
"Attractive",
"Bags_Under_Eyes",
"Bald",
"Bangs",
"Big_Lips",
"Big_Nose",
"Black_Hair",
"Blond_Hair",
"Blurry",
"Brown_Hair",
"Bushy_Eyebrows",
"Chubby",
"Double_Chin",
"Eyeglasses",
"Goatee",
"Gray_Hair",
"Heavy_Makeup",
"High_Cheekbones",
"Male",
"Mouth_Slightly_Open",
"Mustache",
"Narrow_Eyes",
"No_Beard",
"Oval_Face",
"Pale_Skin",
"Pointy_Nose",
"Receding_Hairline",
"Rosy_Cheeks",
"Sideburns",
"Smiling",
"Straight_Hair",
"Wavy_Hair",
"Wearing_Earrings",
"Wearing_Hat",
"Wearing_Lipstick",
"Wearing_Necklace",
"Wearing_Necktie",
"Young",
]

thresholds_mask: dict[str, float] = {}
thresholds_pred: dict[str, float] = {}

# set default thresholds:
for key in sorted(merged_categories.keys()):
thresholds_mask[key] = 0.5
for key in attributes + mask_labels:
if key not in avoided_attributes:
thresholds_pred[key] = 0.5

# set specific thresholds:
thresholds_mask["eye_g"] = 0.5
thresholds_pred["Eyeglasses"] = 0.5
thresholds_pred["Wearing_Earrings"] = 0.5
thresholds_pred["Wearing_Necklace"] = 0.5
thresholds_pred["Wearing_Necktie"] = 0.5


class DeepFashion2GeneralizedCategoriesAndAttributes(CategoriesAndAttributes):
mask_categories = [
"short sleeve top",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,51 +65,6 @@ def _max_value_tuple(some_dict: dict[str, float]) -> tuple[str, float]:
return max_key, some_dict[max_key]


class ImageOfPerson(ImageWithMasksAndAttributes):
def __init__(
self,
image: np.ndarray,
masks: dict[str, np.ndarray],
attributes: dict[str, float],
categories_and_attributes: CategoriesAndAttributes,
):
super().__init__(image, masks, attributes, categories_and_attributes)

@classmethod
def from_parent_instance(
cls, parent_instance: ImageWithMasksAndAttributes
) -> "ImageOfPerson":
"""
Creates an instance of ImageOfPerson using the properties of an
instance of ImageWithMasksAndAttributes.
"""
return cls(
image=parent_instance.image,
masks=parent_instance.masks,
attributes=parent_instance.attributes,
categories_and_attributes=parent_instance.categories_and_attributes,
)

def describe(self) -> dict:
has_hair = self.attributes["hair"] - 0.5
hair_colour = _max_value_tuple(self.selective_attribute_dict["hair_colour"])[0]
hair_shape = _max_value_tuple(self.selective_attribute_dict["hair_shape"])[0]
facial_hair = 1 - self.attributes["No_Beard"] - 0.5
glasses = self.attributes["Eyeglasses"] - 0.5
hat = self.attributes["Wearing_Hat"] - 0.5

result = {
"has_hair": has_hair,
"hair_colour": hair_colour,
"hair_shape": hair_shape,
"facial_hair": facial_hair,
"glasses": glasses,
"hat": hat,
}

return result


class ImageOfCloth(ImageWithMasksAndAttributes):
def __init__(
self,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -152,11 +152,6 @@ def detect_3d(
f"Detected point: {detection.point} of object {detection.name}"
)

# markers.create_and_publish_marker(
# debug_point_publisher,
# PointStamped(point=detection.point, header=pcl_map.header),
# )

detected_objects.append(detection)

# publish to debug topic
Expand Down
Loading

0 comments on commit 64a7495

Please sign in to comment.