Skip to content

Commit

Permalink
Do not allow short if statements on single line (#201)
Browse files Browse the repository at this point in the history
  • Loading branch information
marip8 authored Aug 2, 2024
1 parent 2b828b5 commit 814a973
Show file tree
Hide file tree
Showing 19 changed files with 83 additions and 42 deletions.
2 changes: 1 addition & 1 deletion .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ ConstructorInitializerIndentWidth: 2
AlignEscapedNewlinesLeft: false
AlignTrailingComments: true
AllowAllParametersOfDeclarationOnNextLine: false
AllowShortIfStatementsOnASingleLine: true
AllowShortIfStatementsOnASingleLine: false
AllowShortLoopsOnASingleLine: false
AllowShortFunctionsOnASingleLine: true
AlwaysBreakTemplateDeclarations: true
Expand Down
3 changes: 2 additions & 1 deletion analysis/src/statistics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,8 @@ Eigen::Quaterniond computeQuaternionMean(const std::vector<Eigen::Quaterniond>&
Eigen::Quaterniond q;
q.coeffs() << svd.matrixU().col(0);

if (q.coeffs().array().hasNaN()) throw ICalException("Mean quaternion has NaN values");
if (q.coeffs().array().hasNaN())
throw ICalException("Mean quaternion has NaN values");

return q;
};
Expand Down
3 changes: 2 additions & 1 deletion core/include/industrial_calibration/core/target_finder.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,8 @@ class TargetFinder
typename Correspondence<SENSOR_DIM, WORLD_DIM>::Set findCorrespondences(const SensorDataT& measurement) const
{
TargetFeatures<SENSOR_DIM> features = findTargetFeatures(measurement);
if (features.empty()) throw std::runtime_error("Failed to find any target features");
if (features.empty())
throw std::runtime_error("Failed to find any target features");

return target().createCorrespondences(findTargetFeatures(measurement));
}
Expand Down
3 changes: 2 additions & 1 deletion examples/noise_qualification_2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ PnPNoiseStat run(const path& calibration_file)
try
{
target_features = target_finder->findTargetFeatures(image);
if (target_features.empty()) throw std::runtime_error("Failed to find any target features");
if (target_features.empty())
throw std::runtime_error("Failed to find any target features");
std::cout << "Found " << target_features.size() << " target features" << std::endl;

#ifndef INDUSTRIAL_CALIBRATION_ENABLE_TESTING
Expand Down
6 changes: 4 additions & 2 deletions gui/src/app/camera_intrinsic_calibration_app.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,8 @@ int main(int argc, char** argv)
w.loadObservations(argv[2]);
w.calibrate();
w.saveResults(argv[3]);
if (argc > 4) w.saveROSFormat(argv[4]);
if (argc > 4)
w.saveROSFormat(argv[4]);

QMessageBox::StandardButton ret = QMessageBox::question(nullptr, "Calibration",
"Successfully completed calibration and saved results. "
Expand Down Expand Up @@ -69,7 +70,8 @@ int main(int argc, char** argv)
w.loadConfig(argv[1]);
QMessageBox::information(nullptr, "Configuration", "Successfully loaded calibration configuration");
}
if (argc > 2) w.loadObservations(argv[2]);
if (argc > 2)
w.loadObservations(argv[2]);
}
catch (const std::exception& ex)
{
Expand Down
3 changes: 2 additions & 1 deletion gui/src/app/extrinsic_hand_eye_calibration_app.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,8 @@ int main(int argc, char** argv)
w.loadConfig(argv[1]);
QMessageBox::information(nullptr, "Configuration", "Successfully loaded calibration configuration");
}
if (argc > 2) w.loadObservations(argv[2]);
if (argc > 2)
w.loadObservations(argv[2]);
}
catch (const std::exception& ex)
{
Expand Down
30 changes: 20 additions & 10 deletions gui/src/camera_intrinsic_calibration_widget.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,8 @@ void CameraIntrinsicCalibrationWidget::onLoadConfig()
{
const QString config_file = QFileDialog::getOpenFileName(this, "Load calibration configuration file", QString(),
"YAML files (*.yaml *.yml)");
if (config_file.isNull() || config_file.isEmpty()) return;
if (config_file.isNull() || config_file.isEmpty())
return;

loadConfig(config_file.toStdString());

Expand Down Expand Up @@ -257,7 +258,8 @@ void CameraIntrinsicCalibrationWidget::onLoadObservations()
{
QString observations_file =
QFileDialog::getOpenFileName(this, "Load calibration observation file", QString(), "YAML files (*.yaml *.yml)");
if (observations_file.isNull() || observations_file.isEmpty()) return;
if (observations_file.isNull() || observations_file.isEmpty())
return;

loadObservations(observations_file.toStdString());
}
Expand Down Expand Up @@ -309,7 +311,8 @@ void CameraIntrinsicCalibrationWidget::loadObservations(const std::string& obser

void CameraIntrinsicCalibrationWidget::drawImage(QTreeWidgetItem* item, int col)
{
if (item == nullptr) return;
if (item == nullptr)
return;

// Extract the top level item
while (item->parent() != nullptr)
Expand Down Expand Up @@ -432,7 +435,8 @@ void CameraIntrinsicCalibrationWidget::calibrate()
cv::Mat image = cv::imread(image_file.toStdString());
auto pose = YAML::LoadFile(pose_file.toStdString()).as<Eigen::Isometry3d>();

if (i == 0) image_size = image.size();
if (i == 0)
image_size = image.size();

Correspondence2D3D::Set correspondence_set = target_finder_->findCorrespondences(image);

Expand All @@ -445,7 +449,8 @@ void CameraIntrinsicCalibrationWidget::calibrate()
if (homography_error_mean < ui_->double_spin_box_homography_threshold->value())
{
problem.image_observations.push_back(correspondence_set);
if (problem.use_extrinsic_guesses) problem.extrinsic_guesses.push_back(pose);
if (problem.use_extrinsic_guesses)
problem.extrinsic_guesses.push_back(pose);

info(item, "Included in calibration");
}
Expand Down Expand Up @@ -490,7 +495,8 @@ void CameraIntrinsicCalibrationWidget::onSaveResults()
try
{
const QString file = QFileDialog::getSaveFileName(this, QString(), QString(), "YAML files (*.yaml *.yml)");
if (file.isNull() || file.isEmpty()) return;
if (file.isNull() || file.isEmpty())
return;

saveResults(file.toStdString());
}
Expand All @@ -515,7 +521,8 @@ void CameraIntrinsicCalibrationWidget::onSaveROSFormat()
try
{
const QString file = QFileDialog::getSaveFileName(this, QString(), QString(), "YAML files (*.yaml *.yml)");
if (file.isNull() || file.isEmpty()) return;
if (file.isNull() || file.isEmpty())
return;

saveROSFormat(file.toStdString());
}
Expand All @@ -527,7 +534,8 @@ void CameraIntrinsicCalibrationWidget::onSaveROSFormat()

void CameraIntrinsicCalibrationWidget::saveROSFormat(const std::string& file) const
{
if (result_ == nullptr) return;
if (result_ == nullptr)
return;

Eigen::Matrix<double, 3, 4, Eigen::RowMajor> mat;
mat << result_->intrinsics.fx(), 0.0, result_->intrinsics.cx(), 0.0, 0.0, result_->intrinsics.fy(),
Expand All @@ -539,11 +547,13 @@ void CameraIntrinsicCalibrationWidget::saveROSFormat(const std::string& file) co

// Image size
{
if (ui_->tree_widget_observations->topLevelItemCount() == 0) throw ICalException("No observations have been added");
if (ui_->tree_widget_observations->topLevelItemCount() == 0)
throw ICalException("No observations have been added");

QTreeWidgetItem* item = ui_->tree_widget_observations->topLevelItem(0);
QString image_file = item->data(0, IMAGE_FILE_NAME_ROLE).value<QString>();
if (!QFile(image_file).exists()) throw ICalException("Image '" + image_file.toStdString() + "' does not exist");
if (!QFile(image_file).exists())
throw ICalException("Image '" + image_file.toStdString() + "' does not exist");

cv::Mat image = cv::imread(image_file.toStdString());
node["image_height"] = image.size[0];
Expand Down
12 changes: 8 additions & 4 deletions gui/src/extrinsic_hand_eye_calibration_widget.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,8 @@ void ExtrinsicHandEyeCalibrationWidget::onLoadConfig()
// Get yaml filepath
const QString config_file = QFileDialog::getOpenFileName(this, "Load calibration configuration file", QString(),
"YAML files (*.yaml *.yml)");
if (config_file.isNull() || config_file.isEmpty()) return;
if (config_file.isNull() || config_file.isEmpty())
return;

loadConfig(config_file.toStdString());

Expand Down Expand Up @@ -198,7 +199,8 @@ void ExtrinsicHandEyeCalibrationWidget::onLoadObservations()
{
QString observations_file =
QFileDialog::getOpenFileName(this, "Load calibration observation file", QString(), "YAML files (*.yaml *.yml)");
if (observations_file.isNull() || observations_file.isEmpty()) return;
if (observations_file.isNull() || observations_file.isEmpty())
return;

loadObservations(observations_file.toStdString());
}
Expand Down Expand Up @@ -250,7 +252,8 @@ void ExtrinsicHandEyeCalibrationWidget::loadObservations(const std::string& obse

void ExtrinsicHandEyeCalibrationWidget::drawImage(QTreeWidgetItem* item, int col)
{
if (item == nullptr) return;
if (item == nullptr)
return;

// Extract the top level item
while (item->parent() != nullptr)
Expand Down Expand Up @@ -441,7 +444,8 @@ void ExtrinsicHandEyeCalibrationWidget::onSaveResults()
try
{
const QString file = QFileDialog::getSaveFileName(this, QString(), QString(), "YAML files (*.yaml *.yml)");
if (file.isNull() || file.isEmpty()) return;
if (file.isNull() || file.isEmpty())
return;

saveResults(file.toStdString());
}
Expand Down
3 changes: 2 additions & 1 deletion gui/src/target_finder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,8 @@ void TargetFinderWidget::configure(const YAML::Node& node)
// Target
QString target_type = QString::fromStdString(getMember<std::string>(node, "type"));
int idx = ui_->combo_box_target_finder->findText(target_type);
if (idx < 0) throw std::runtime_error("Unknown target type '" + target_type.toStdString() + "'");
if (idx < 0)
throw std::runtime_error("Unknown target type '" + target_type.toStdString() + "'");

dynamic_cast<ConfigurableWidget*>(ui_->stacked_widget->widget(idx))->configure(node);
ui_->combo_box_target_finder->setCurrentIndex(idx);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,8 @@ struct EigenQuaternionPlus
*/
void addSubsetParameterization(ceres::Problem& problem, const std::map<const double*, std::vector<int>>& param_masks)
{
if (param_masks.empty()) return;
if (param_masks.empty())
return;

std::vector<double*> parameter_blocks;
problem.GetParameterBlocks(&parameter_blocks);
Expand Down
3 changes: 2 additions & 1 deletion optimizations/src/camera_intrinsic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,8 @@ static Pose6d solvePnP(const CameraIntrinsics& intr, const Correspondence2D3D::S

PnPResult result = optimize(problem);

if (!result.converged) throw ICalException("Unable to solve PnP sub-problem");
if (!result.converged)
throw ICalException("Unable to solve PnP sub-problem");

return poseEigenToCal(result.camera_to_target);
}
Expand Down
9 changes: 6 additions & 3 deletions optimizations/src/covariance_analysis.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,10 @@ Eigen::MatrixXd computeCorrelationsFromCovariance(const Eigen::MatrixXd& covaria
out(static_cast<Eigen::Index>(i), static_cast<Eigen::Index>(j)) = sigma_i;
else
{
if (sigma_i < std::numeric_limits<double>::epsilon()) sigma_i = 1;
if (sigma_j < std::numeric_limits<double>::epsilon()) sigma_j = 1;
if (sigma_i < std::numeric_limits<double>::epsilon())
sigma_i = 1;
if (sigma_j < std::numeric_limits<double>::epsilon())
sigma_j = 1;

out(static_cast<Eigen::Index>(i), static_cast<Eigen::Index>(j)) = covariance_matrix(i, j) / (sigma_i * sigma_j);
}
Expand Down Expand Up @@ -163,7 +165,8 @@ CovarianceResult computeCovariance(ceres::Problem& problem, const std::vector<co
// Extract tangent space
std::vector<int> masks;
auto it = param_masks.find(b);
if (it != param_masks.end()) masks = it->second;
if (it != param_masks.end())
masks = it->second;

const std::vector<std::string>& label = param_names.at(b);
for (std::size_t i = 0; i < static_cast<std::size_t>(block_size); ++i)
Expand Down
3 changes: 2 additions & 1 deletion optimizations/src/covariance_types.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@ std::vector<NamedParam> CovarianceResult::getCorrelationCoeffOutsideThreshold(co
std::vector<NamedParam> out;
for (auto corr : correlation_coeffs)
{
if (std::abs(corr.value) > threshold) out.push_back(corr);
if (std::abs(corr.value) > threshold)
out.push_back(corr);
}
std::sort(out.begin(), out.end(), [](NamedParam a, NamedParam b) { return std::abs(a.value) > std::abs(b.value); });
return out;
Expand Down
15 changes: 10 additions & 5 deletions optimizations/src/dh_chain_kinematic_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,8 @@ void printOptimizationLabels(ceres::Problem& problem, const std::map<const doubl
sub_label.reserve(label.size());
for (std::size_t j = 0; j < label.size(); ++j)
{
if (std::find(mask.begin(), mask.end(), j) == mask.end()) sub_label.push_back(label.at(j));
if (std::find(mask.begin(), mask.end(), j) == mask.end())
sub_label.push_back(label.at(j));
}
}
}
Expand Down Expand Up @@ -192,8 +193,10 @@ KinematicCalibrationResult optimize(const KinematicCalibrationProblem2D3D& param
}

// Tell the optimization to keep constant the dummy DH offsets that might have been added to the 0-DoF chains
if (params.camera_chain.dof() == 0) problem.SetParameterBlockConstant(camera_chain_dh_offsets.data());
if (params.target_chain.dof() == 0) problem.SetParameterBlockConstant(target_chain_dh_offsets.data());
if (params.camera_chain.dof() == 0)
problem.SetParameterBlockConstant(camera_chain_dh_offsets.data());
if (params.target_chain.dof() == 0)
problem.SetParameterBlockConstant(target_chain_dh_offsets.data());

// Add subset parameterization to mask variables that shouldn't be optimized
addSubsetParameterization(problem, param_masks);
Expand Down Expand Up @@ -401,8 +404,10 @@ KinematicCalibrationResult optimize(const KinematicCalibrationProblemPose6D& par
}

// Tell the optimization to keep constant the dummy DH offsets that might have been added to the 0-DoF chains
if (params.camera_chain.dof() == 0) problem.SetParameterBlockConstant(camera_chain_dh_offsets.data());
if (params.target_chain.dof() == 0) problem.SetParameterBlockConstant(target_chain_dh_offsets.data());
if (params.camera_chain.dof() == 0)
problem.SetParameterBlockConstant(camera_chain_dh_offsets.data());
if (params.target_chain.dof() == 0)
problem.SetParameterBlockConstant(target_chain_dh_offsets.data());

// Add subset parameterization to mask variables that shouldn't be optimized
addSubsetParameterization(problem, param_masks);
Expand Down
15 changes: 10 additions & 5 deletions target_finders/opencv/src/circle_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,8 @@ DetectionResult findCircles(const cv::Mat& image, const double threshold, const
if (params.filterByArea)
{
double area = moms.m00;
if (area < params.minArea || area >= params.maxArea) continue;
if (area < params.minArea || area >= params.maxArea)
continue;
}

// Circularity filter
Expand All @@ -117,7 +118,8 @@ DetectionResult findCircles(const cv::Mat& image, const double threshold, const
double area = moms.m00;
double perimeter = cv::arcLength(cv::Mat(contour), true);
double ratio = 4 * CV_PI * area / (perimeter * perimeter);
if (ratio < params.minCircularity || ratio >= params.maxCircularity) continue;
if (ratio < params.minCircularity || ratio >= params.maxCircularity)
continue;
}

// Inertia filter
Expand All @@ -142,7 +144,8 @@ DetectionResult findCircles(const cv::Mat& image, const double threshold, const
ratio = 1;
}

if (ratio < params.minInertiaRatio || ratio >= params.maxInertiaRatio) continue;
if (ratio < params.minInertiaRatio || ratio >= params.maxInertiaRatio)
continue;
}

// Convexity filter
Expand All @@ -153,7 +156,8 @@ DetectionResult findCircles(const cv::Mat& image, const double threshold, const
double area = cv::contourArea(cv::Mat(contour));
double hullArea = cv::contourArea(cv::Mat(hull));
double ratio = area / hullArea;
if (ratio < params.minConvexity || ratio >= params.maxConvexity) continue;
if (ratio < params.minConvexity || ratio >= params.maxConvexity)
continue;
}

// Fit an ellipse to the contour
Expand All @@ -162,7 +166,8 @@ DetectionResult findCircles(const cv::Mat& image, const double threshold, const
// Check that the color of the center pixel matches the expectation
if (params.filterByColor)
{
if (binarized_image.at<uchar>(cvRound(box.center.y), cvRound(box.center.x)) != params.circleColor) continue;
if (binarized_image.at<uchar>(cvRound(box.center.y), cvRound(box.center.x)) != params.circleColor)
continue;
}

// Check that the contour matches a model of an ellipse within tolerance
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -387,7 +387,8 @@ static std::vector<cv::Point2d> extractModifiedCircleGrid(const cv::Mat& image,
}
}

if (centers.size() == 0) throw ICalException("Failed to find circle centers");
if (centers.size() == 0)
throw ICalException("Failed to find circle centers");

return extractKeyPoints(image, centers, detector_ptr, rows, cols, flipped);
}
Expand Down
3 changes: 2 additions & 1 deletion target_finders/opencv/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,8 @@ void drawReprojections(const VectorVector2d& reprojections, int size, cv::Scalar
cv::Mat readImageOpenCV(const std::string& path)
{
cv::Mat image = cv::imread(path, cv::IMREAD_COLOR);
if (image.data == nullptr) throw BadFileException("Failed to load file at: '" + path + "'");
if (image.data == nullptr)
throw BadFileException("Failed to load file at: '" + path + "'");

return image;
}
Expand Down
3 changes: 2 additions & 1 deletion test/pnp_utest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,8 @@ void checkCorrelation(const Eigen::MatrixXd& cov)
for (Eigen::Index col = 0; col < cov.cols(); ++col)
{
// Since the covariance matrix is symmetric, just check the values in the top triangle
if (row < col) EXPECT_LT(std::abs(cov(row, col)), CORRELATION_COEFFICIENT_THRESHOLD);
if (row < col)
EXPECT_LT(std::abs(cov(row, col)), CORRELATION_COEFFICIENT_THRESHOLD);
}
}
}
Expand Down
3 changes: 2 additions & 1 deletion test/serialization_utest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,8 @@ template <class T>
void serialize(const std::string& file, const T& val)
{
std::ofstream ofh(file);
if (!ofh) throw ICalException("Failed to open file '" + file + "'");
if (!ofh)
throw ICalException("Failed to open file '" + file + "'");

YAML::Node n = YAML::Node(val);
ofh << n;
Expand Down

0 comments on commit 814a973

Please sign in to comment.