Skip to content

Commit

Permalink
fix: minor linting and codestyle changes
Browse files Browse the repository at this point in the history
  • Loading branch information
dfbakin committed Jul 18, 2024
1 parent de1d343 commit 5c19feb
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 22 deletions.
16 changes: 7 additions & 9 deletions packages/camera/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@ project(camera)
add_compile_options(-Wall -Wextra -Werror=unused-variable -Wpedantic)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pthread")

# find_package(cv_bridge REQUIRED)
find_package(OpenCV REQUIRED)
find_package(yaml_cpp_vendor REQUIRED)
find_package(ament_cmake REQUIRED)
Expand All @@ -26,23 +25,22 @@ target_include_directories(

target_include_directories(
calibration PUBLIC "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"/usr/include"
"/usr/include"
)
target_include_directories(
triangulation PUBLIC "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"/usr/include")
"/usr/include"
)

ament_target_dependencies(camera yaml_cpp_vendor)
ament_target_dependencies(calibration yaml_cpp_vendor Boost OpenCV)

ament_target_dependencies(
triangulation
OpenCV
yaml_cpp_vendor)
ament_target_dependencies(triangulation OpenCV yaml_cpp_vendor)

target_link_libraries(camera mvsdk)

install(TARGETS camera calibration triangulation DESTINATION lib/${PROJECT_NAME})
install(TARGETS camera calibration triangulation
DESTINATION lib/${PROJECT_NAME}
)

if(NOT EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/params")
file(MAKE_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/params")
Expand Down
5 changes: 2 additions & 3 deletions packages/camera/include/triangulation.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ struct StereoParameters {

class TriangulationNode {
public:
TriangulationNode(std::string &params_file_path, std::vector<int> camera_ids);
TriangulationNode(std::string& params_file_path, std::vector<int> camera_ids);

cv::Point3f triangulatePosition(std::vector<cv::Point2f> image_points);

Expand All @@ -25,6 +25,5 @@ class TriangulationNode {
std::vector<StereoParameters> camera_stereo_params = {};
std::vector<cv::Mat> projection_matrices = {};
} param_{};

};
} // namespace handy
} // namespace handy
12 changes: 6 additions & 6 deletions packages/camera/src/params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,12 @@
namespace handy {

CameraIntrinsicParameters::CameraIntrinsicParameters(
cv::Size size, cv::Mat camera_matr, const cv::Vec<double, 5>& distort_coefs, const int cam_id)
: image_size(size)
, camera_matrix(std::move(camera_matr))
, camera_matrix_inv(camera_matrix.inv())
, dist_coefs(distort_coefs)
, camera_id(cam_id) {}
cv::Size size, cv::Mat camera_matr, const cv::Vec<double, 5>& distort_coefs, const int cam_id) :
image_size(size),
camera_matrix(std::move(camera_matr)),
camera_matrix_inv(camera_matrix.inv()),
dist_coefs(distort_coefs),
camera_id(cam_id) {}

void CameraIntrinsicParameters::storeYaml(const std::string& yaml_path) const {
const std::string camera_id_str = std::to_string(camera_id);
Expand Down
8 changes: 4 additions & 4 deletions packages/camera/src/triangulation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ TriangulationNode::TriangulationNode(std::string& params_file_path, std::vector<
printf("only 2 cameras are supported\n");
exit(EXIT_FAILURE);
}
for (int i = 0; i < camera_ids.size(); ++i) {
for (size_t i = 0; i < camera_ids.size(); ++i) {
param_.cameras_intrinsics.push_back(
CameraIntrinsicParameters::loadFromYaml(params_file_path, camera_ids[i]));
param_.camera_stereo_params.emplace_back();
Expand Down Expand Up @@ -85,7 +85,7 @@ int main(int argc, char* argv[]) {
}
std::sort(filenames.begin(), filenames.end());

printf("%d\n", filenames.size());
printf("%ld\n", filenames.size());

std::string path_file_param(argv[1]);
handy::TriangulationNode triangulation_node(path_file_param, {1, 2});
Expand All @@ -94,7 +94,7 @@ int main(int argc, char* argv[]) {
json triangulation_json;
triangulation_json["triangulated_points"] = {};

for (int i = 0; i < filenames.size(); ++i) {
for (size_t i = 0; i < filenames.size(); ++i) {
std::string current_filename = filenames[i];
cv::Point2f first_image_point{
detections_1_json[current_filename]["centroid"][0],
Expand Down Expand Up @@ -155,4 +155,4 @@ int main(int argc, char* argv[]) {
detections_2_json_file.close();

return 0;
}
}

0 comments on commit 5c19feb

Please sign in to comment.