Skip to content

Commit

Permalink
Fix warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
niosus committed May 13, 2020
1 parent 75c5729 commit e26c460
Show file tree
Hide file tree
Showing 12 changed files with 110 additions and 112 deletions.
9 changes: 4 additions & 5 deletions src/ground_removal/depth_ground_remover.cpp
Expand Up @@ -24,24 +24,23 @@

#include <algorithm>

#include "utils/velodyne_utils.h"
#include "image_labelers/linear_image_labeler.h"
#include "image_labelers/diff_helpers/angle_diff.h"
#include "image_labelers/diff_helpers/simple_diff.h"
#include "image_labelers/linear_image_labeler.h"
#include "utils/timer.h"
#include "utils/velodyne_utils.h"

namespace depth_clustering {

using cv::Mat;
using cv::DataType;
using cv::Mat;
using std::to_string;
using time_utils::Timer;

const cv::Point ANCHOR_CENTER = cv::Point(-1, -1);
const int SAME_OUTPUT_TYPE = -1;

void DepthGroundRemover::OnNewObjectReceived(const Cloud& cloud,
const int sender_id) {
void DepthGroundRemover::OnNewObjectReceived(const Cloud& cloud, const int) {
// this can be done even faster if we switch to column-major implementation
// thus allowing us to load whole row in L1 cache
if (!cloud.projection_ptr()) {
Expand Down
2 changes: 1 addition & 1 deletion src/qt/widgets/base_viewer_widget.cpp
Expand Up @@ -24,7 +24,7 @@

BaseViewerWidget::BaseViewerWidget(QWidget *parent) : QWidget(parent) {}

bool BaseViewerWidget::eventFilter(QObject *object, QEvent *event) {
bool BaseViewerWidget::eventFilter(QObject *, QEvent *event) {
if (event->type() == QEvent::KeyPress) {
QKeyEvent *keyEvent = static_cast<QKeyEvent *>(event);
if (keyEvent->key() == Qt::Key_Right || keyEvent->key() == Qt::Key_Left) {
Expand Down
6 changes: 3 additions & 3 deletions src/visualization/cloud_saver.cpp
Expand Up @@ -25,7 +25,7 @@
namespace depth_clustering {

void VectorCloudSaver::OnNewObjectReceived(
const std::unordered_map<uint16_t, Cloud>& clouds, const int id) {
const std::unordered_map<uint16_t, Cloud>& clouds, const int) {
if (_folder_counter++ % _save_every > 0) {
// nope, skip this one
return;
Expand Down Expand Up @@ -53,7 +53,7 @@ std::string VectorCloudSaver::WithLeadingZerosStr(int num) {
}

void DepthMapSaver::OnNewObjectReceived(
const std::unordered_map<uint16_t, cv::Mat>& clusters, const int id) {
const std::unordered_map<uint16_t, cv::Mat>& clusters, const int) {
if (_folder_counter++ % _save_every > 0) {
// nope, skip this one
return;
Expand All @@ -79,7 +79,7 @@ std::string DepthMapSaver::WithLeadingZerosStr(int num) {
.append(counter_str);
}

void CloudSaver::OnNewObjectReceived(const Cloud& cloud, const int id) {
void CloudSaver::OnNewObjectReceived(const Cloud& cloud, const int) {
pcl::io::savePCDFileBinary(
_prefix + "_" + std::to_string(_counter++) + ".pcd", *(cloud.ToPcl()));
}
Expand Down
4 changes: 2 additions & 2 deletions src/visualization/visualizer.cpp
Expand Up @@ -148,7 +148,7 @@ void Visualizer::DrawCube(const Eigen::Vector3f& center,

Visualizer::~Visualizer() {}

void Visualizer::OnNewObjectReceived(const Cloud& cloud, const int id) {
void Visualizer::OnNewObjectReceived(const Cloud& cloud, const int) {
lock_guard<mutex> guard(_cloud_mutex);
_cloud = cloud;
}
Expand All @@ -161,7 +161,7 @@ unordered_map<uint16_t, Cloud> ObjectPtrStorer::object_clouds() const {
}

void ObjectPtrStorer::OnNewObjectReceived(
const unordered_map<uint16_t, Cloud>& clouds, const int id) {
const unordered_map<uint16_t, Cloud>& clouds, const int) {
lock_guard<mutex> guard(_cluster_mutex);
_obj_clouds = clouds;

Expand Down
4 changes: 2 additions & 2 deletions test/test_angle_diff.cpp
Expand Up @@ -51,7 +51,7 @@ TEST(AngleDiff, AlphasRows) {
SpanParams::Direction::HORIZONTAL);
TestAngleDiff angle_diff_helper(&depth_image, &params);
auto alphas_rows = angle_diff_helper.GetRowAlphas();
EXPECT_EQ(4, alphas_rows.size());
EXPECT_EQ(4ul, alphas_rows.size());
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_rows[0], 0.001);
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_rows[1], 0.001);
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_rows[2], 0.001);
Expand All @@ -68,7 +68,7 @@ TEST(AngleDiff, AlphasCols) {
SpanParams::Direction::HORIZONTAL);
TestAngleDiff angle_diff_helper(&depth_image, &params);
auto alphas_cols = angle_diff_helper.GetColAlphas();
EXPECT_EQ(4, alphas_cols.size());
EXPECT_EQ(4ul, alphas_cols.size());
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_cols[0], 0.001);
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_cols[1], 0.001);
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_cols[2], 0.001);
Expand Down
8 changes: 4 additions & 4 deletions test/test_cloud.cpp
Expand Up @@ -40,7 +40,7 @@ TEST(CloudTest, InitEmpty) {
EXPECT_NEAR(0.0, cloud.pose().x(), eps);
EXPECT_NEAR(0.0, cloud.pose().y(), eps);
EXPECT_NEAR(0.0, cloud.pose().theta(), eps);
EXPECT_EQ(0, cloud.size());
EXPECT_EQ(0ul, cloud.size());
}

TEST(CloudTest, InitPose) {
Expand All @@ -53,7 +53,7 @@ TEST(CloudTest, InitPose) {
EXPECT_NEAR(1, cloud.pose().x(), eps);
EXPECT_NEAR(2, cloud.pose().y(), eps);
EXPECT_NEAR(M_PI / 3, cloud.pose().theta(), eps);
EXPECT_EQ(0, cloud.size());
EXPECT_EQ(0ul, cloud.size());
}

TEST(CloudTest, InitCloudWithPose) {
Expand All @@ -67,7 +67,7 @@ TEST(CloudTest, InitCloudWithPose) {
EXPECT_NEAR(1, cloud.pose().x(), eps);
EXPECT_NEAR(2, cloud.pose().y(), eps);
EXPECT_NEAR(M_PI / 3, cloud.pose().theta(), eps);
EXPECT_EQ(1, cloud.size());
EXPECT_EQ(1ul, cloud.size());
}

TEST(CloudTest, CloudCopy) {
Expand All @@ -86,7 +86,7 @@ TEST(CloudTest, CloudCopy) {
EXPECT_NEAR(1, cloud_copy[0].x(), eps);
EXPECT_NEAR(2, cloud_copy[0].y(), eps);
EXPECT_NEAR(3, cloud_copy[0].z(), eps);
EXPECT_EQ(1, cloud.size());
EXPECT_EQ(1ul, cloud.size());
}

TEST(CloudTest, EmptyCloudProjectionPixels) {
Expand Down
142 changes: 71 additions & 71 deletions test/test_cloud_projection.cpp
Expand Up @@ -54,18 +54,18 @@ TEST(CloudProjectionTest, SingleLine) {
cloud_ptr->InitProjection(params);
auto projection = cloud_ptr->projection_ptr();

EXPECT_EQ(1, projection->rows());
EXPECT_EQ(10, projection->cols());
EXPECT_EQ(0, projection->at(0, 0).points().front());
EXPECT_EQ(1, projection->at(0, 1).points().front());
EXPECT_EQ(2, projection->at(0, 2).points().front());
EXPECT_EQ(3, projection->at(0, 3).points().front());
EXPECT_EQ(4, projection->at(0, 4).points().front());
EXPECT_EQ(5, projection->at(0, 5).points().front());
EXPECT_EQ(6, projection->at(0, 6).points().front());
EXPECT_EQ(7, projection->at(0, 7).points().front());
EXPECT_EQ(8, projection->at(0, 8).points().front());
EXPECT_EQ(9, projection->at(0, 9).points().front());
EXPECT_EQ(1ul, projection->rows());
EXPECT_EQ(10ul, projection->cols());
EXPECT_EQ(0ul, projection->at(0, 0).points().front());
EXPECT_EQ(1ul, projection->at(0, 1).points().front());
EXPECT_EQ(2ul, projection->at(0, 2).points().front());
EXPECT_EQ(3ul, projection->at(0, 3).points().front());
EXPECT_EQ(4ul, projection->at(0, 4).points().front());
EXPECT_EQ(5ul, projection->at(0, 5).points().front());
EXPECT_EQ(6ul, projection->at(0, 6).points().front());
EXPECT_EQ(7ul, projection->at(0, 7).points().front());
EXPECT_EQ(8ul, projection->at(0, 8).points().front());
EXPECT_EQ(9ul, projection->at(0, 9).points().front());
}

TEST(CloudProjectionTest, PlanePatch) {
Expand Down Expand Up @@ -93,37 +93,37 @@ TEST(CloudProjectionTest, PlanePatch) {
SphericalProjection storage(params);
storage.InitFromPoints(cloud_ptr->points());

EXPECT_EQ(5, storage.rows());
EXPECT_EQ(5, storage.cols());
EXPECT_EQ(0, storage.at(0, 0).points().front());
EXPECT_EQ(1, storage.at(0, 1).points().front());
EXPECT_EQ(2, storage.at(0, 2).points().front());
EXPECT_EQ(3, storage.at(0, 3).points().front());
EXPECT_EQ(4, storage.at(0, 4).points().front());

EXPECT_EQ(5, storage.at(1, 0).points().front());
EXPECT_EQ(6, storage.at(1, 1).points().front());
EXPECT_EQ(7, storage.at(1, 2).points().front());
EXPECT_EQ(8, storage.at(1, 3).points().front());
EXPECT_EQ(9, storage.at(1, 4).points().front());

EXPECT_EQ(10, storage.at(2, 0).points().front());
EXPECT_EQ(11, storage.at(2, 1).points().front());
EXPECT_EQ(12, storage.at(2, 2).points().front());
EXPECT_EQ(13, storage.at(2, 3).points().front());
EXPECT_EQ(14, storage.at(2, 4).points().front());

EXPECT_EQ(15, storage.at(3, 0).points().front());
EXPECT_EQ(16, storage.at(3, 1).points().front());
EXPECT_EQ(17, storage.at(3, 2).points().front());
EXPECT_EQ(18, storage.at(3, 3).points().front());
EXPECT_EQ(19, storage.at(3, 4).points().front());

EXPECT_EQ(20, storage.at(4, 0).points().front());
EXPECT_EQ(21, storage.at(4, 1).points().front());
EXPECT_EQ(22, storage.at(4, 2).points().front());
EXPECT_EQ(23, storage.at(4, 3).points().front());
EXPECT_EQ(24, storage.at(4, 4).points().front());
EXPECT_EQ(5ul, storage.rows());
EXPECT_EQ(5ul, storage.cols());
EXPECT_EQ(0ul, storage.at(0, 0).points().front());
EXPECT_EQ(1ul, storage.at(0, 1).points().front());
EXPECT_EQ(2ul, storage.at(0, 2).points().front());
EXPECT_EQ(3ul, storage.at(0, 3).points().front());
EXPECT_EQ(4ul, storage.at(0, 4).points().front());

EXPECT_EQ(5ul, storage.at(1, 0).points().front());
EXPECT_EQ(6ul, storage.at(1, 1).points().front());
EXPECT_EQ(7ul, storage.at(1, 2).points().front());
EXPECT_EQ(8ul, storage.at(1, 3).points().front());
EXPECT_EQ(9ul, storage.at(1, 4).points().front());

EXPECT_EQ(10ul, storage.at(2, 0).points().front());
EXPECT_EQ(11ul, storage.at(2, 1).points().front());
EXPECT_EQ(12ul, storage.at(2, 2).points().front());
EXPECT_EQ(13ul, storage.at(2, 3).points().front());
EXPECT_EQ(14ul, storage.at(2, 4).points().front());

EXPECT_EQ(15ul, storage.at(3, 0).points().front());
EXPECT_EQ(16ul, storage.at(3, 1).points().front());
EXPECT_EQ(17ul, storage.at(3, 2).points().front());
EXPECT_EQ(18ul, storage.at(3, 3).points().front());
EXPECT_EQ(19ul, storage.at(3, 4).points().front());

EXPECT_EQ(20ul, storage.at(4, 0).points().front());
EXPECT_EQ(21ul, storage.at(4, 1).points().front());
EXPECT_EQ(22ul, storage.at(4, 2).points().front());
EXPECT_EQ(23ul, storage.at(4, 3).points().front());
EXPECT_EQ(24ul, storage.at(4, 4).points().front());
}

TEST(CloudProjectionTest, Circle) {
Expand All @@ -146,18 +146,18 @@ TEST(CloudProjectionTest, Circle) {
SphericalProjection storage(params);
storage.InitFromPoints(cloud_ptr->points());

EXPECT_EQ(1, storage.rows());
EXPECT_EQ(12, storage.cols());
EXPECT_EQ(0, storage.at(0, 0).points().front());
EXPECT_EQ(1, storage.at(0, 1).points().front());
EXPECT_EQ(2, storage.at(0, 2).points().front());
EXPECT_EQ(3, storage.at(0, 3).points().front());
EXPECT_EQ(4, storage.at(0, 4).points().front());
EXPECT_EQ(5, storage.at(0, 5).points().front());
EXPECT_EQ(6, storage.at(0, 6).points().front());
EXPECT_EQ(7, storage.at(0, 7).points().front());
EXPECT_EQ(8, storage.at(0, 8).points().front());
EXPECT_EQ(9, storage.at(0, 9).points().front());
EXPECT_EQ(1ul, storage.rows());
EXPECT_EQ(12ul, storage.cols());
EXPECT_EQ(0ul, storage.at(0, 0).points().front());
EXPECT_EQ(1ul, storage.at(0, 1).points().front());
EXPECT_EQ(2ul, storage.at(0, 2).points().front());
EXPECT_EQ(3ul, storage.at(0, 3).points().front());
EXPECT_EQ(4ul, storage.at(0, 4).points().front());
EXPECT_EQ(5ul, storage.at(0, 5).points().front());
EXPECT_EQ(6ul, storage.at(0, 6).points().front());
EXPECT_EQ(7ul, storage.at(0, 7).points().front());
EXPECT_EQ(8ul, storage.at(0, 8).points().front());
EXPECT_EQ(9ul, storage.at(0, 9).points().front());
}

TEST(CloudProjectionTest, BigCylinder) {
Expand Down Expand Up @@ -190,15 +190,15 @@ TEST(CloudProjectionTest, BigCylinder) {
SphericalProjection storage(params);
storage.InitFromPoints(cloud_ptr->points());

EXPECT_EQ(12, storage.rows());
EXPECT_EQ(12, storage.cols());
EXPECT_EQ(12ul, storage.rows());
EXPECT_EQ(12ul, storage.cols());

// first 5 points
EXPECT_EQ(0, storage.at(0, 0).points().front());
EXPECT_EQ(1, storage.at(0, 1).points().front());
EXPECT_EQ(2, storage.at(0, 2).points().front());
EXPECT_EQ(3, storage.at(0, 3).points().front());
EXPECT_EQ(4, storage.at(0, 4).points().front());
EXPECT_EQ(0ul, storage.at(0, 0).points().front());
EXPECT_EQ(1ul, storage.at(0, 1).points().front());
EXPECT_EQ(2ul, storage.at(0, 2).points().front());
EXPECT_EQ(3ul, storage.at(0, 3).points().front());
EXPECT_EQ(4ul, storage.at(0, 4).points().front());
}

TEST(CloudProjectionTest, FullSphere) {
Expand Down Expand Up @@ -233,15 +233,15 @@ TEST(CloudProjectionTest, FullSphere) {
Mat image = storage.depth_image();
cv::imwrite("sphere.png", image);

EXPECT_EQ(12, storage.rows());
EXPECT_EQ(12, storage.cols());
EXPECT_EQ(12ul, storage.rows());
EXPECT_EQ(12ul, storage.cols());

// first 5 points
EXPECT_EQ(0, storage.at(0, 0).points().front());
EXPECT_EQ(1, storage.at(0, 1).points().front());
EXPECT_EQ(2, storage.at(0, 2).points().front());
EXPECT_EQ(3, storage.at(0, 3).points().front());
EXPECT_EQ(4, storage.at(0, 4).points().front());
EXPECT_EQ(0ul, storage.at(0, 0).points().front());
EXPECT_EQ(1ul, storage.at(0, 1).points().front());
EXPECT_EQ(2ul, storage.at(0, 2).points().front());
EXPECT_EQ(3ul, storage.at(0, 3).points().front());
EXPECT_EQ(4ul, storage.at(0, 4).points().front());

float eps = 0.001;
EXPECT_NEAR(image.at<float>(0, 0), radius, eps);
Expand Down Expand Up @@ -284,8 +284,8 @@ TEST(CloudProjectionTest, FromDepthImage) {
auto cloud = Cloud::FromImage(image, params);
auto projection = cloud->projection_ptr();
cv::Mat image_res = projection->depth_image();
EXPECT_EQ(10, projection->rows());
EXPECT_EQ(10, projection->cols());
EXPECT_EQ(10ul, projection->rows());
EXPECT_EQ(10ul, projection->cols());
for (int i = 0; i < 10; ++i) {
EXPECT_EQ(image.at<float>(i, 0), image_res.at<float>(i, 0));
EXPECT_EQ(image.at<float>(0, i), image_res.at<float>(0, i));
Expand Down
4 changes: 2 additions & 2 deletions test/test_image_clusterer.cpp
Expand Up @@ -40,7 +40,7 @@ TEST(LinearImageLabeler, NeighborhoodTest) {
Radians threshold = 20_deg;
ProjectionParams params;
LinearImageLabeler<1, 1> labeler(depth_image, params, threshold);
EXPECT_EQ(4, labeler.Neighborhood.size());
EXPECT_EQ(4ul, labeler.Neighborhood.size());

EXPECT_EQ(-1, labeler.Neighborhood[0].row);
EXPECT_EQ(0, labeler.Neighborhood[0].col);
Expand All @@ -61,7 +61,7 @@ TEST(LinearImageLabeler, NeighborhoodTestBigger) {
Radians threshold = 20_deg;
ProjectionParams params;
LinearImageLabeler<2, 1> labeler(depth_image, params, threshold);
EXPECT_EQ(6, labeler.Neighborhood.size());
EXPECT_EQ(6ul, labeler.Neighborhood.size());

EXPECT_EQ(-2, labeler.Neighborhood[0].row);
EXPECT_EQ(0, labeler.Neighborhood[0].col);
Expand Down
4 changes: 2 additions & 2 deletions test/test_line_dist_diff.cpp
Expand Up @@ -51,7 +51,7 @@ TEST(LineDistDiff, AlphasRows) {
SpanParams::Direction::HORIZONTAL);
TestLineDistDiff angle_diff_helper(&depth_image, &params);
auto alphas_rows = angle_diff_helper.GetRowAlphas();
EXPECT_EQ(4, alphas_rows.size());
EXPECT_EQ(4ul, alphas_rows.size());
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_rows[0], 0.001);
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_rows[1], 0.001);
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_rows[2], 0.001);
Expand All @@ -68,7 +68,7 @@ TEST(LineDistDiff, AlphasCols) {
SpanParams::Direction::HORIZONTAL);
TestLineDistDiff angle_diff_helper(&depth_image, &params);
auto alphas_cols = angle_diff_helper.GetColAlphas();
EXPECT_EQ(4, alphas_cols.size());
EXPECT_EQ(4ul, alphas_cols.size());
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_cols[0], 0.001);
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_cols[1], 0.001);
EXPECT_NEAR(Radians::FromDegrees(1).val(), alphas_cols[2], 0.001);
Expand Down
1 change: 0 additions & 1 deletion test/test_pose.cpp
Expand Up @@ -291,7 +291,6 @@ TEST(PoseTest, V2T2V) {
// More: http://en.cppreference.com/w/cpp/error/assert
#ifndef NDEBUG
TEST(PoseDeathTest, TestLikelihood) {
double eps = 0.000001;
Pose pose;
ASSERT_DEATH(pose.SetLikelihood(2), "");
ASSERT_DEATH(pose.SetLikelihood(-1), "");
Expand Down

0 comments on commit e26c460

Please sign in to comment.