Skip to content

Commit

Permalink
plotting changes and opencv upgrade
Browse files Browse the repository at this point in the history
  • Loading branch information
raphaelchang committed Nov 5, 2019
1 parent b17d3a2 commit 8de98e9
Show file tree
Hide file tree
Showing 9 changed files with 140 additions and 69 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ find_package(catkin REQUIRED COMPONENTS ${REQ_CATKIN_PKGS})
find_package(Eigen3 REQUIRED)
include_directories(${EIGEN3_INCLUDE_DIR})

find_package(OpenCV 3.3 REQUIRED)
find_package(OpenCV 4.1 REQUIRED)
include_directories(${OpenCV_INCLUDE_DIRS})
link_directories(${OpenCV_LIBRARIES_DIRS})

Expand Down
2 changes: 1 addition & 1 deletion launch/slam_eval.launch
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
tracker_checker_epipolar_threshold: 0.008
tracker_checker_iterations: 1000
tracker_delta_pixel_error_threshold: 0.0
tracker_error_threshold: 128
tracker_error_threshold: 20.0
min_features_per_region: 100
max_features_per_region: 1000
odometry_type: 'pnp'
Expand Down
159 changes: 105 additions & 54 deletions scripts/matching_eval_plot.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@

parser = argparse.ArgumentParser(description='Plot matching evaluation results')
parser.add_argument('results_path', help='matching results file, source bag file, or working directory')
parser.add_argument('--detector_descriptor', help='detector+descriptor type for bag file')
parser.add_argument('--fov', help='fov for bag file')
args = parser.parse_args()

if not os.path.isdir(args.results_path) and args.results_path.endswith('.hdf5'):
Expand Down Expand Up @@ -181,10 +183,20 @@
rec = dict()
detdesclist = []
for filename in os.listdir(os.path.dirname(args.results_path)):
if filename.startswith(os.path.basename(args.results_path)) and filename.endswith('.matching.hdf5'):
bagname = os.path.splitext(os.path.basename(args.results_path))[0]
if args.fov is not None:
bagname += '.' + args.fov
if filename.startswith(bagname) and filename.endswith('.matching.hdf5'):
with h5py.File(os.path.join(os.path.dirname(args.results_path), filename), 'r') as f:
if args.fov is None:
fov = int(filename[len(bagname):].split('.')[1])
else:
fov = int(args.fov)
attrs = dict(f['attributes'].attrs.items())
detdesc = (attrs['detector_type'], attrs['descriptor_type'])
if args.detector_descriptor is not None:
if attrs['detector_type'] + '_' + attrs['descriptor_type'] != args.detector_descriptor:
continue
detdesc = (attrs['detector_type'], attrs['descriptor_type'], fov)
detdesclist.append(detdesc)
stats = f['match_stats'][:]
radial_overlaps_errors[detdesc] = f['radial_overlaps_errors'][:]
Expand All @@ -196,9 +208,25 @@
statsavg = df.groupby(0).mean().to_records()
statsavg = statsavg.view(np.float64).reshape(len(statsavg), -1)
framediff[detdesc], nmatch[detdesc], prec[detdesc], rec[detdesc] = statsavg.T

if len(detdesclist) > 0:
fig = plt.figure()
fig.suptitle('Matching - chi={}, alpha={}, fx={}, fy={}, cx={}, cy={}'.format(attrs["chi"][0], attrs["alpha"][0], attrs["fx"][0], attrs["fy"][0], attrs["cx"][0], attrs["cy"][0]))

detdesclist = sorted(detdesclist)
legendlist = []
if args.fov is not None:
legendlist = ['{}+{}'.format(det, desc) for det, desc, fov in detdesclist]
legendtitle = 'Detector+Descriptor'
fig.suptitle('Matching - Statistics for various detector+descriptors for FOV {}'.format(args.fov))
elif args.detector_descriptor is not None:
legendlist = [int(fov) for det, desc, fov in detdesclist]
legendtitle = 'FOV'
fig.suptitle('Matching - Statistics for {}+{} for various FOVs'.format(args.detector_descriptor.split('_')[0], args.detector_descriptor.split('_')[1]))
else:
legendlist = ['{}+{} {}'.format(det, desc, fov) for det, desc, fov in detdesclist]
legendtitle = 'Detector+Descriptor+FOV'
fig.suptitle('Matching - Statistics for various detector+descriptors and FOVs')

ax1 = fig.add_subplot(3, 2, 1)
ax2 = fig.add_subplot(3, 2, 2)
ax3 = fig.add_subplot(3, 2, 3)
Expand All @@ -220,7 +248,7 @@
h2, = ax1.plot(framediff[detdesc] * attrs["rate"][0], rec[detdesc], linestyle='dashed', color=color)
handles.append((h1, h2))

l1 = ax1.legend(handles, ['{}+{}'.format(det, desc) for det, desc in detdesclist], loc=1, title='Detector+Descriptor', fontsize='small')
l1 = ax1.legend(handles, legendlist, loc=1, title=legendtitle, fontsize='small')
l2 = ax1.legend([h1, h2], ['Precision', 'Recall'], loc=4, fontsize='small')
l2.legendHandles[0].set_color('black')
l2.legendHandles[1].set_color('black')
Expand All @@ -235,7 +263,7 @@
h, = ax2.plot(framediff[detdesc] * attrs["rate"][0], nmatch[detdesc], color=color)
handles.append(h)

l1 = ax2.legend(handles, ['{}+{}'.format(det, desc) for det, desc in detdesclist], loc=1, title='Detector+Descriptor', fontsize='small')
l1 = ax2.legend(handles, legendlist, loc=1, title=legendtitle, fontsize='small')
ax2.add_artist(l1)
ax2.set_xlabel('Frame difference')
ax2.set_ylabel('Number of matches')
Expand All @@ -252,69 +280,92 @@
y, x = np.absolute(rocc[rocc[:, 1] == i][:, 2:].T)
h, = ax3.plot(x, y, color=color)
handles.append(h)
l1 = ax3.legend(handles, ['{}+{}'.format(det, desc) for det, desc in detdesclist], loc=1, title='Detector+Descriptor', fontsize='small')
l1 = ax3.legend(handles, legendlist, loc=1, title=legendtitle, fontsize='small')
ax3.add_artist(l1)

df = pd.DataFrame()
for detdesc in detdesclist:
df = df.append(pd.DataFrame({'Detector+Descriptor': ['{}+{}'.format(detdesc[0], detdesc[1]) for i in range(len(good_radial_distances[detdesc]))], 'Delta radial distance': good_radial_distances[detdesc][:, 0]}))
sns.violinplot(x='Detector+Descriptor', y='Delta radial distance', data=df, ax=ax4, palette="muted")
for d, detdesc in enumerate(detdesclist):
df = df.append(pd.DataFrame({legendtitle: [legendlist[d] for i in range(len(good_radial_distances[detdesc]))], 'Delta radial distance': good_radial_distances[detdesc][:, 0]}))
sns.violinplot(x=legendtitle, y='Delta radial distance', data=df, ax=ax4, palette="muted")
ax4.grid(which='major', linestyle='--', axis='y', linewidth=0.5)
ax4.set_axisbelow(True)
ax4.set_title('Distribution of matches over changes in radial distance')

df = pd.DataFrame()
for detdesc in detdesclist:
for d, detdesc in enumerate(detdesclist):
matches = np.hstack((good_radial_distances[detdesc][:, 1], bad_radial_distances[detdesc][:, 1]))
matches /= matches.max()
df = df.append(pd.DataFrame({'Detector+Descriptor': ['{}+{}'.format(detdesc[0], detdesc[1]) for i in range(len(matches))], 'Normalized descriptor distance': matches, 'Match': ['Good' for i in range(len(good_radial_distances[detdesc]))] + ['Bad' for i in range(len(bad_radial_distances[detdesc]))]}))
sns.violinplot(x="Detector+Descriptor", y="Normalized descriptor distance", hue="Match", data=df, split=True, ax=ax5, palette="Set2", inner="quart")
df = df.append(pd.DataFrame({legendtitle: [legendlist[d] for i in range(len(matches))], 'Normalized descriptor distance': matches, 'Match': ['Good' for i in range(len(good_radial_distances[detdesc]))] + ['Bad' for i in range(len(bad_radial_distances[detdesc]))]}))
sns.violinplot(x=legendtitle, y="Normalized descriptor distance", hue="Match", data=df, split=True, ax=ax5, palette="Set2", inner="quart")
handles, labels = ax5.get_legend_handles_labels()
ax5.legend(handles=handles[0:], labels=labels[0:], fontsize='small')
ax5.set_title('Distribution of good and bad matches over descriptor distances')

ax6.set_title('Match separability over changes in radial distance')
ax6.set_ylabel('Silhouette coefficient')
ax6.set_xlabel('Delta radial distance')
handles = []
for detdesc in detdesclist:
num_bins = 50
num_samples = 1000
sr = [0 for i in range(num_bins)]
X_good = [np.array([]) for i in range(num_bins)]
labels_good = [np.array([]) for i in range(num_bins)]
X_bad = [np.array([]) for i in range(num_bins)]
labels_bad = [np.array([]) for i in range(num_bins)]
valid_good = [False for i in range(num_bins)]
valid_bad = [False for i in range(num_bins)]
valid = [False for i in range(num_bins)]
for row in good_radial_distances[detdesc]:
r = int(min(row[0], 0.499999) / (0.5 / num_bins))
X_good[r] = np.append(X_good[r], row[1])
labels_good[r] = np.append(labels_good[r], 0)
valid_good[r] = True
for row in bad_radial_distances[detdesc]:
r = int(min(row[0], 0.499999) / (0.5 / num_bins))
X_bad[r] = np.append(X_bad[r], row[1])
labels_bad[r] = np.append(labels_bad[r], 1)
valid_bad[r] = True
for i in range(num_bins):
valid[i] = valid_good[i] and valid_bad[i]
if not valid[i]:
continue
idx_good = np.arange(len(X_good[i]))
idx_bad = np.arange(len(X_bad[i]))
if len(X_good[i]) > num_samples:
idx_good = np.random.choice(np.arange(len(X_good[i])), num_samples, replace=False)
if len(X_bad[i]) > num_samples:
idx_bad = np.random.choice(np.arange(len(X_bad[i])), num_samples, replace=False)
sr[i] = sklearn.metrics.silhouette_score(np.concatenate((X_good[i][idx_good], X_bad[i][idx_bad])).reshape(-1, 1), np.concatenate((labels_good[i][idx_good], labels_bad[i][idx_bad])), metric = 'l1')
# sr[i] = sklearn.metrics.davies_bouldin_score(X[i].reshape(-1, 1), labels[i])
color = next(ax6._get_lines.prop_cycler)['color']
h, = ax6.plot([i * 0.5 / num_bins + 0.5 / num_bins / 2 for i in range(0, len(sr)) if valid[i]], [sr[i] for i in range(0, len(sr)) if valid[i]], color=color)
handles.append(h)
l1 = ax6.legend(handles, ['{}+{}'.format(det, desc) for det, desc in detdesclist], loc=1, title='Detector+Descriptor', fontsize='small')
ax6.add_artist(l1)
if args.fov is not None or args.detector_descriptor is not None:
ax6.set_title('Descriptor separability over changes in radial distance')
ax6.set_ylabel('Silhouette coefficient')
ax6.set_xlabel('Delta radial distance')
handles = []
for detdesc in detdesclist:
num_bins = 50
num_samples = 1000
sr = [0 for i in range(num_bins)]
X_good = [np.array([]) for i in range(num_bins)]
labels_good = [np.array([]) for i in range(num_bins)]
X_bad = [np.array([]) for i in range(num_bins)]
labels_bad = [np.array([]) for i in range(num_bins)]
valid_good = [False for i in range(num_bins)]
valid_bad = [False for i in range(num_bins)]
valid = [False for i in range(num_bins)]
for row in good_radial_distances[detdesc]:
r = int(min(row[0], 0.499999) / (0.5 / num_bins))
X_good[r] = np.append(X_good[r], row[1])
labels_good[r] = np.append(labels_good[r], 0)
valid_good[r] = True
for row in bad_radial_distances[detdesc]:
r = int(min(row[0], 0.499999) / (0.5 / num_bins))
X_bad[r] = np.append(X_bad[r], row[1])
labels_bad[r] = np.append(labels_bad[r], 1)
valid_bad[r] = True
for i in range(num_bins):
valid[i] = valid_good[i] and valid_bad[i]
if not valid[i]:
continue
idx_good = np.arange(len(X_good[i]))
idx_bad = np.arange(len(X_bad[i]))
if len(X_good[i]) > num_samples:
idx_good = np.random.choice(np.arange(len(X_good[i])), num_samples, replace=False)
if len(X_bad[i]) > num_samples:
idx_bad = np.random.choice(np.arange(len(X_bad[i])), num_samples, replace=False)
sr[i] = sklearn.metrics.silhouette_score(np.concatenate((X_good[i][idx_good], X_bad[i][idx_bad])).reshape(-1, 1), np.concatenate((labels_good[i][idx_good], labels_bad[i][idx_bad])), metric = 'l1')
# sr[i] = sklearn.metrics.davies_bouldin_score(X[i].reshape(-1, 1), labels[i])
color = next(ax6._get_lines.prop_cycler)['color']
h, = ax6.plot([i * 0.5 / num_bins + 0.5 / num_bins / 2 for i in range(0, len(sr)) if valid[i]], [sr[i] for i in range(0, len(sr)) if valid[i]], color=color)
handles.append(h)
l1 = ax6.legend(handles, legendlist, loc=1, title=legendtitle, fontsize='small')
ax6.add_artist(l1)
else:
ax6.set_title('Descriptor separability over FOV')
df = pd.DataFrame()
for detdesc in detdesclist:
num_samples = 1000
labels_good = []
labels_bad = []
for row in good_radial_distances[detdesc]:
labels_good.append(0)
for row in bad_radial_distances[detdesc]:
labels_bad.append(1)
labels_good = np.array(labels_good)
labels_bad = np.array(labels_bad)
idx_good = np.arange(len(good_radial_distances[detdesc]))
idx_bad = np.arange(len(bad_radial_distances[detdesc]))
if len(idx_good) > num_samples:
idx_good = np.random.choice(np.arange(len(idx_good)), num_samples, replace=False)
if len(idx_bad) > num_samples:
idx_bad = np.random.choice(np.arange(len(idx_bad)), num_samples, replace=False)
s = sklearn.metrics.silhouette_score(np.concatenate((good_radial_distances[detdesc][idx_good, 1], bad_radial_distances[detdesc][idx_bad, 1])).reshape(-1, 1), np.concatenate((labels_good[idx_good], labels_bad[idx_bad])), metric = 'l1')
df = df.append(pd.DataFrame({'Detector+Descriptor': ['{}+{}'.format(detdesc[0], detdesc[1])], 'Silhouette coefficient': [s], 'FOV': [detdesc[2]]}))
sns.catplot(x='FOV', y='Silhouette coefficient', hue='Detector+Descriptor', data=df, ax=ax6, palette="muted", kind='bar')

plt.show()

Expand Down
6 changes: 3 additions & 3 deletions src/data/frame.cc
Original file line number Diff line number Diff line change
Expand Up @@ -336,14 +336,14 @@ void Frame::DecompressImages()
{
return;
}
image_ = cv::imdecode(cv::Mat(1, imageComp_.size(), CV_8UC1, imageComp_.data()), CV_LOAD_IMAGE_UNCHANGED);
image_ = cv::imdecode(cv::Mat(1, imageComp_.size(), CV_8UC1, imageComp_.data()), cv::IMREAD_UNCHANGED);
if (hasDepth_)
{
depthImage_ = cv::imdecode(cv::Mat(1, depthImageComp_.size(), CV_8UC1, depthImageComp_.data()), CV_LOAD_IMAGE_UNCHANGED);
depthImage_ = cv::imdecode(cv::Mat(1, depthImageComp_.size(), CV_8UC1, depthImageComp_.data()), cv::IMREAD_UNCHANGED);
}
if (hasStereo_)
{
stereoImage_ = cv::imdecode(cv::Mat(1, stereoImageComp_.size(), CV_8UC1, stereoImageComp_.data()), CV_LOAD_IMAGE_UNCHANGED);
stereoImage_ = cv::imdecode(cv::Mat(1, stereoImageComp_.size(), CV_8UC1, stereoImageComp_.data()), cv::IMREAD_UNCHANGED);
}
imageComp_.clear();
depthImageComp_.clear();
Expand Down
12 changes: 6 additions & 6 deletions src/feature/detector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,7 @@ Detector::Detector(std::string detector_type, std::string descriptor_type, std::
}
else
{
detector_ = cv::AKAZE::create(cv::AKAZE::DESCRIPTOR_MLDB, 0, 3, det_args["threshold"], (int)det_args["nOctaves"], (int)det_args["nOctaveLayers"], (int)det_args["diffusivity"]);
detector_ = cv::AKAZE::create(cv::AKAZE::DESCRIPTOR_MLDB, 0, 3, det_args["threshold"], (int)det_args["nOctaves"], (int)det_args["nOctaveLayers"], (cv::KAZE::DiffusivityType)det_args["diffusivity"]);
}
}
else if (detector_type == "KAZE")
Expand All @@ -180,7 +180,7 @@ Detector::Detector(std::string detector_type, std::string descriptor_type, std::
}
else
{
detector_ = cv::KAZE::create(false, false, det_args["threshold"], (int)det_args["nOctaves"], (int)det_args["nOctaveLayers"], (int)det_args["diffusivity"]);
detector_ = cv::KAZE::create(false, false, det_args["threshold"], (int)det_args["nOctaves"], (int)det_args["nOctaveLayers"], (cv::KAZE::DiffusivityType)det_args["diffusivity"]);
}
}
else if (detector_type == "AGAST")
Expand Down Expand Up @@ -279,7 +279,7 @@ Detector::Detector(std::string detector_type, std::string descriptor_type, std::
}
else
{
descriptor_ = cv::AKAZE::create(cv::AKAZE::DESCRIPTOR_MLDB, 0, 3, 0.001f, (int)desc_args["nOctaves"], (int)desc_args["nOctaveLayers"], (int)desc_args["diffusivity"]);
descriptor_ = cv::AKAZE::create(cv::AKAZE::DESCRIPTOR_MLDB, 0, 3, 0.001f, (int)desc_args["nOctaves"], (int)desc_args["nOctaveLayers"], (cv::KAZE::DiffusivityType)desc_args["diffusivity"]);
}
}
else if (descriptor_type == "KAZE")
Expand All @@ -298,7 +298,7 @@ Detector::Detector(std::string detector_type, std::string descriptor_type, std::
}
else
{
descriptor_ = cv::KAZE::create(false, false, desc_args["threshold"], (int)desc_args["nOctaves"], (int)desc_args["nOctaveLayers"], (int)desc_args["diffusivity"]);
descriptor_ = cv::KAZE::create(false, false, desc_args["threshold"], (int)desc_args["nOctaves"], (int)desc_args["nOctaveLayers"], (cv::KAZE::DiffusivityType)desc_args["diffusivity"]);
}
}
else if (descriptor_type == "DAISY")
Expand All @@ -325,7 +325,7 @@ Detector::Detector(std::string detector_type, std::string descriptor_type, std::
}
else
{
descriptor_ = cv::xfeatures2d::DAISY::create((int)desc_args["radius"], (int)desc_args["q_radius"], (int)desc_args["q_theta"], (int)desc_args["q_hist"], (int)desc_args["norm"], cv::noArray(), true, true);
descriptor_ = cv::xfeatures2d::DAISY::create((int)desc_args["radius"], (int)desc_args["q_radius"], (int)desc_args["q_theta"], (int)desc_args["q_hist"], (cv::xfeatures2d::DAISY::NormalizationType)desc_args["norm"], cv::noArray(), true, true);
}
}
else if (descriptor_type == "FREAK")
Expand Down Expand Up @@ -482,7 +482,7 @@ int Detector::DetectInRegion(data::Frame &frame, std::vector<data::Landmark> &la
if (descriptorType_ == "LUCID")
{
cv::Mat rgb;
cv::cvtColor(img, rgb, CV_GRAY2BGR);
cv::cvtColor(img, rgb, cv::COLOR_GRAY2BGR);
descriptor_->compute(rgb, kpts, descs);
}
else
Expand Down
Loading

0 comments on commit 8de98e9

Please sign in to comment.