Skip to content

Commit

Permalink
Merge pull request #223 from mhwasil/melodic
Browse files Browse the repository at this point in the history
[perception] use model dir from mir_perception_models
  • Loading branch information
mhwasil authored Oct 18, 2021
2 parents 76ed0e0 + 26e1da1 commit 799e197
Show file tree
Hide file tree
Showing 7 changed files with 36 additions and 109 deletions.
2 changes: 2 additions & 0 deletions mir_perception/mir_object_recognition/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@
<build_depend>roslint</build_depend>
<build_depend>mir_object_segmentation</build_depend>
<build_depend>mir_perception_utils</build_depend>
<build_depend>mir_rgb_object_recognition_models</build_depend>
<build_depend>mir_pointcloud_object_recognition_models</build_depend>

<build_export_depend>cv_bridge</build_export_depend>
<build_export_depend>geometry_msgs</build_export_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
<arg name="input_pointcloud_topic" default="/arm_cam3d/depth_registered/points" />
<arg name="input_image_topic" default="/arm_cam3d/rgb/image_raw" />
<arg name="target_frame" default="base_link" />
<!-- for intel realsense d435, use fixed_camera_link as pointcloud_source_frame_id (bug from robocup 2021) -->
<arg name="pointcloud_source_frame_id" default="arm_cam3d_rgb_optical_frame" />
<arg name="debug_mode" default="true" />
<arg name="scene_segmentation_config_file" default="$(find mir_object_recognition)/ros/config/scene_segmentation_constraints.yaml" />
<arg name="object_info" default="$(find mir_object_recognition)/ros/config/objects.xml" />
Expand All @@ -18,6 +20,7 @@
<remap from="~input_image_topic" to="$(arg input_image_topic)" />
<remap from="~output/object_list" to="/mcr_perception/object_detector/object_list"/>
<param name="target_frame_id" value="$(arg target_frame)" type="str" />
<param name="pointcloud_source_frame_id" value="$(arg pointcloud_source_frame_id)" type="str" />
<param name="debug_mode" value="$(arg debug_mode)" type="bool" />
<param name="dataset_collection" value="true" />
<param name="logdir" value="/tmp/" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,15 @@
<arg name="target_frame" default="odom" />
<arg name="model" default="cnn_based" />
<arg name="model_id" default="dgcnn" />
<arg name="dataset" default="asus" />
<arg name="dataset" default="all" />
<arg name="model_dir" default="$(find mir_pointcloud_object_recognition_models)/common/models/$(arg model_id)/$(arg dataset)" />

<group ns="mir_perception">
<node pkg="mir_object_recognition" type="pc_object_recognizer_node" name="pc_object_recognizer_node" output="screen"
respawn="false" ns="multimodal_object_recognition/recognizer/pc">
<param name="model" value="$(arg model)" type="str" />
<param name="model_id" value="$(arg model_id)" type="str" />
<param name="model_dir" value="$(arg model_dir)" type="str" />
<param name="dataset" value="$(arg dataset)" type="str" />
<remap from="~input/object_list" to="/mir_perception/multimodal_object_recognition/recognizer/pc/input/object_list" />
<remap from="~output/object_list" to="/mir_perception/multimodal_object_recognition/recognizer/pc/output/object_list"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,16 @@
<launch>
<arg name="net" default="detection" />
<arg name="classifier" default="squeezeDet" />
<arg name="dataset_type" default="stable" />
<arg name="dataset" default="stable" />
<arg name="model_dir" default="$(find mir_rgb_object_recognition_models)/common/models/$(arg classifier)/$(arg dataset)" />

<group ns="mir_perception">
<node pkg="mir_object_recognition" type="rgb_object_recognizer_node" name="rgb_object_recognizer" output="screen"
respawn="false" ns="multimodal_object_recognition/recognizer/rgb">
<param name="net" value="$(arg net)" type="str" />
<param name="classifier" value="$(arg classifier)" type="str" />
<param name="dataset_type" value="$(arg dataset_type)" type="str" />
<param name="dataset" value="$(arg dataset)" type="str" />
<param name="model_dir" value="$(arg model_dir)" type="str" />
<remap from="~input/images" to="/mir_perception/multimodal_object_recognition/recognizer/rgb/input/images" />
<remap from="~output/object_list" to="/mir_perception/multimodal_object_recognition/recognizer/rgb/output/object_list"/>
</node>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
#!/usr/bin/env python

PACKAGE = 'mir_object_recognition'
NODE = 'pc_object_recognizer'

import colorsys
import importlib
import os
Expand Down Expand Up @@ -33,17 +30,13 @@ class PointcloudObjectRecognizer():
:param variance: Variance of gmm model for FV
"""

def __init__(self, model, model_id, dataset, ngaussians=2, variance=0.05):
def __init__(self, model, model_id, dataset, model_dir, ngaussians=2, variance=0.05):
self.model = model
dataset_dir = model_id + "_" + dataset
cfg_folder = os.path.join(roslib.packages.get_pkg_dir(PACKAGE), 'common', 'config')
#cfg_folder = os.path.join(roslib.packages.get_pkg_dir("mir_object_recognition"), 'common', 'config')

model_config_file = os.path.join(roslib.packages.get_pkg_dir(PACKAGE),
model_config_file = os.path.join(roslib.packages.get_pkg_dir("mir_object_recognition"),
'ros', 'config', "pc_classifier_config.yaml")

#threshold for alu profile color
#black < 0.3, gray >= 03
self.alu_profile_color_th = 0.3

if os.path.isfile(model_config_file):
configs = {}
Expand All @@ -66,12 +59,12 @@ class PointcloudObjectRecognizer():
elif model_id == "rdd":
feature_extraction.set_rdd_params(color=True)

classifier_file = os.path.join(cfg_folder, dataset_dir, 'classifier.joblib')
label_encoder = os.path.join(cfg_folder, dataset_dir, 'label_encoder.joblib')
classifier_file = os.path.join(model_dir, 'classifier.pkl')
label_encoder = os.path.join(model_dir, 'label_encoder.pkl')
self.classifier = FeatureBasedClassifiers(classifier_file, label_encoder)

elif model == "cnn_based":
checkpoint = os.path.join(cfg_folder, dataset_dir , 'model.ckpt')
checkpoint = os.path.join(model_dir , 'model.ckpt')
module_name = "pc_object_recognition" + "." + model_id.lower()+"_"+"classifier"
class_name = model_id.upper()+"Classifier"
ClassifierClass = getattr(importlib.import_module(module_name), class_name)
Expand All @@ -95,33 +88,19 @@ class PointcloudObjectRecognizer():
recognized_object_list = object_list.objects
for object in recognized_object_list:
if self.model == "feature_based":
cloud = self.extract_pointcloud(object.views[0].point_cloud, color="rgb")
cloud = self.extract_pointcloud(object.views[0].point_cloud, color="hsv")
features = self.fe_method(cloud)
features = np.reshape(features, (1,-1))
name, probability = self.classifier.classify(features)
name = self.label_to_name[name[0]]
name = name[0]
elif self.model == "cnn_based":
cloud = self.extract_pointcloud(object.views[0].point_cloud, color="rgb")
label, probability = self.classifier.classify(cloud, center=True, rotate=True, pad=True)
name = self.label_to_name[label]

# check if it's profile, replace the recognition result if
# it's misclassified with color according to threshold
if "S40_40" in name or "F20_20" in name:
median_color = np.median(cloud[:,3:], axis=0)
mean_median_color = np.mean(median_color)
rospy.loginfo("Checking color for %s: mean_median_color= %s", name, mean_median_color)

if mean_median_color < self.alu_profile_color_th and "G" in name:
new_label = name.replace("G", "B", 1)
name = new_label
elif mean_median_color > self.alu_profile_color_th and "B" in name:
new_label = name.replace("B", "G", 1)
name = new_label

object.name = name
object.probability = probability

self.pub.publish(recognized_object_list)

def extract_pointcloud(self, pc, color="hsv"):
Expand Down Expand Up @@ -153,11 +132,13 @@ class PointcloudObjectRecognizer():
return pointcloud

if __name__ == '__main__':
rospy.init_node(NODE)
rospy.init_node('pc_object_recognizer')

model = rospy.get_param("~model")
model_id = rospy.get_param("~model_id")
model_dir = rospy.get_param("~model_dir")
dataset = rospy.get_param("~dataset")
object_recognizer = PointcloudObjectRecognizer(model, model_id, dataset)
#rospy.loginfo('\033[92m'+"PCL Recognizer is ready using: %s , model: %s ", model, model_id)

object_recognizer = PointcloudObjectRecognizer(model, model_id, dataset, model_dir)
rospy.loginfo("PCL Recognizer is ready using: %s , model: %s ", model, model_id)
rospy.spin()
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
#!/usr/bin/env python

PACKAGE = "mir_object_recognition"

import colorsys
import os
import pickle
Expand Down Expand Up @@ -31,7 +29,7 @@ class RGBObjectRecognizer():
self.net = net
self.model_name = model_name

config_file = os.path.join(roslib.packages.get_pkg_dir(PACKAGE),
config_file = os.path.join(roslib.packages.get_pkg_dir("mir_object_recognition"),
'ros', 'config', "rgb_classifier_config.yaml")

if os.path.isfile(config_file):
Expand Down Expand Up @@ -76,12 +74,6 @@ class RGBObjectRecognizer():
result.roi = roi
objects.append(result)

# remove overlapping bboxes
idxs_to_remove, objects = self.remove_overlapping_bbox(objects)
bboxes = [bbox for i,bbox in enumerate(bboxes) if i not in idxs_to_remove]
probs = [prob for i,prob in enumerate(probs) if i not in idxs_to_remove]
labels = [label for i,label in enumerate(labels) if i not in idxs_to_remove]

# Publish result_list
result_list.objects = objects
self.pub_result.publish(result_list)
Expand All @@ -104,66 +96,6 @@ class RGBObjectRecognizer():

elif self.net == 'classification':
print "TODO: MobileNet"

def remove_overlapping_bbox(self, objects):
"""
Remove object which has bigger intersection areas
Args:
objects: object_list
Returns:
indices: object indices to remove
filtered_objects: objects filtered
"""
object_to_remove_idxs = []
for i,object_1 in enumerate(objects):
for j,object_2 in enumerate(objects):
if i != j:
bbox1 = [object_1.roi.x_offset,object_1.roi.y_offset,
object_1.roi.width,object_1.roi.height]
bbox2 = [object_2.roi.x_offset,object_2.roi.y_offset,
object_2.roi.width,object_2.roi.height]

intersection = float(self.compute_intersection(bbox1, bbox2))
if intersection > 1e-2:
intersection_over_area1 = intersection / (object_1.roi.height * object_1.roi.width)
intersection_over_area2 = intersection / (object_2.roi.height * object_2.roi.width)

if intersection_over_area1 >= intersection_over_area2:
if i not in object_to_remove_idxs:
object_to_remove_idxs.append(i)
else:
if i not in object_to_remove_idxs:
object_to_remove_idxs.append(j)

filtered_objects = []
for i,obj in enumerate(objects):
if i not in object_to_remove_idxs:
filtered_objects.append(obj)

return object_to_remove_idxs, filtered_objects

def compute_intersection(self, box1, box2):
"""
Compute iou
Args:
box1: array of 4 elements [cx, cy, width, height].
box2: same as above
Returns:
iou: a float number in range [0, 1]. iou of the two boxes.
"""

lr = min(box1[0]+box1[2], box2[0]+box2[2]) - \
max(box1[0], box2[0])
if lr > 0:
tb = min(box1[1]+box1[3], box2[1]+box2[3]) - \
max(box1[1], box2[1])
if tb > 0:
intersection = tb*lr
union = box1[2]*box1[3]+box2[2]*box2[3]-intersection

return float(intersection)

return 0

def publish_debug_img(self, debug_img):
debug_img = np.array(debug_img, dtype=np.uint8)
Expand All @@ -175,9 +107,9 @@ if __name__ == '__main__':
rospy.loginfo('Started object recognition node.')
net = rospy.get_param("~net")
classifier_name = rospy.get_param("~classifier")
dataset_type = rospy.get_param("~dataset_type")
dataset_dir = os.path.join(roslib.packages.get_pkg_dir(PACKAGE), 'common', 'config', classifier_name, dataset_type)
dataset = rospy.get_param("~dataset")
model_dir = rospy.get_param("~model_dir")

object_recognizer = RGBObjectRecognizer(model_dir=dataset_dir, net=net, model_name=classifier_name, debug_mode=True)
rospy.loginfo('\033[92m'+"RGB Recognizer is ready using %s : %s , dataset: %s ", net, classifier_name, dataset_type)
object_recognizer = RGBObjectRecognizer(model_dir=model_dir, net=net, model_name=classifier_name, debug_mode=True)
rospy.loginfo('\033[92m'+"RGB Recognizer is ready using %s : %s , dataset: %s ", net, classifier_name, dataset)
rospy.spin()
5 changes: 5 additions & 0 deletions repository.rosinstall
Original file line number Diff line number Diff line change
Expand Up @@ -102,3 +102,8 @@
local-name: atwork-commander
uri: https://github.com/robocup-at-work/atwork-commander.git
version: master

- git:
local-name: mir_perception_models
uri: https://github.com/b-it-bots/mir_perception_models.git
version: main

0 comments on commit 799e197

Please sign in to comment.