From 891f57b49f6b11bcc2e8832942cdaa01278eabc0 Mon Sep 17 00:00:00 2001 From: Quinn Pfeifer <72775766+QuinnP2910@users.noreply.github.com> Date: Mon, 22 Jan 2024 13:10:18 -0800 Subject: [PATCH] Improve compiler warning flags (#296) * Change to CXX flags to add_compile_options, add many more warnings, and take away -Wno flags * Get rid of conversion and pedantic warnings * Add -Werror and add "unsed" attributes * Test -Werror making GitHub format check fail * Add -Werror back * Change "unused" notation * Fix formatting * Remove "unused" tags and fix CameraParams assignment operator * Fix formatting * Actually remove the "unused" tags --- src/CAN/FakeCANBoard.cpp | 4 +++- src/CMakeLists.txt | 13 +++++------ src/ar/ARTester.cpp | 4 ++-- src/camera/CameraParams.cpp | 32 ++++++++++++++++++-------- src/camera/CameraParams.h | 11 +++++++-- src/network/MissionControlProtocol.cpp | 8 +++---- 6 files changed, 46 insertions(+), 26 deletions(-) diff --git a/src/CAN/FakeCANBoard.cpp b/src/CAN/FakeCANBoard.cpp index 097deaf7c..85b190d19 100644 --- a/src/CAN/FakeCANBoard.cpp +++ b/src/CAN/FakeCANBoard.cpp @@ -162,9 +162,11 @@ int main() { // get y data: set point (target vel * time since set velocity call) + initial pos double setPoint = (targetVel * util::durationToSec(currTime - startTime)) + initialMotorPos.getData(); + LOG_F(INFO, "Set point: %f", setPoint); // get y data: motor position robot::types::DataPoint motorPos = motor->getMotorPos(); + LOG_F(INFO, "Motor position: %d", motorPos.getData()); // check if time is up double elapsedTime = util::durationToSec(currTime - startTime); @@ -224,7 +226,7 @@ int main() { can::deviceid_t id = std::make_pair(can::devicegroup_t::motor, serial); can::addDeviceTelemetryCallback( id, can::telemtype_t::limit_switch, - [](can::deviceid_t id, can::telemtype_t telemType, + [](can::deviceid_t id, [[maybe_unused]] can::telemtype_t telemType, DataPoint data) { std::cout << "Motor Limit: serial=" << std::hex << static_cast(id.second) diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 2a103d779..6e03cafd7 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -126,13 +126,6 @@ if(WORLD_INTERFACE STREQUAL "REAL") endif() endif() -# Enable all warnings except a few (unused variable/parameter/result) -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall \ --Wno-unused-variable \ --Wno-unused-but-set-variable \ --Wno-unused-result \ --Wno-unused-parameter") # -Wconversion") - if(WITH_TESTS) enable_testing() endif() @@ -360,6 +353,12 @@ if (WORLD_INTERFACE STREQUAL "REAL") target_link_libraries(LimitSwitchCalibration real_world_interface) endif() +add_compile_options( + -Wall + -Wextra + -Werror +) + add_subdirectory(ar) add_subdirectory(camera) add_subdirectory(CAN) diff --git a/src/ar/ARTester.cpp b/src/ar/ARTester.cpp index e648adac3..866682dd9 100644 --- a/src/ar/ARTester.cpp +++ b/src/ar/ARTester.cpp @@ -1,6 +1,6 @@ #include "../camera/Camera.h" -#include "../camera/CameraParams.h" #include "../camera/CameraConfig.h" +#include "../camera/CameraParams.h" #include "Detector.h" #include @@ -109,7 +109,7 @@ int main(int argc, char* argv[]) { cam_config.release(); cv::Mat frame; - uint32_t fnum = 0; + [[maybe_unused]] uint32_t fnum = 0; std::cout << "Opening camera..." << std::endl; bool open_success = false; diff --git a/src/camera/CameraParams.cpp b/src/camera/CameraParams.cpp index 94d5d6fda..5cb419732 100644 --- a/src/camera/CameraParams.cpp +++ b/src/camera/CameraParams.cpp @@ -1,17 +1,17 @@ #include "CameraParams.h" -#include "../../src/camera/CameraConfig.h" #include "../../src/Constants.h" -#include +#include "../../src/camera/CameraConfig.h" #include +#include + namespace cam { ////////////// CONSTRUCTORS ////////////// -CameraParams::CameraParams() { -} +CameraParams::CameraParams() {} void CameraParams::init(const cv::Mat& camera_matrix, const cv::Mat& dist_coeff, cv::Size image_size) { @@ -66,16 +66,26 @@ cv::Size CameraParams::getImageSize() const { return _image_size; } -std::vector CameraParams::getIntrinsicList(){ +std::vector CameraParams::getIntrinsicList() { std::vector intrinsic_list1D; - for (int i = 0; i < 3; i++){ - for (int j = 0; j < 3; j++){ - double x = _camera_matrix.at(i,j); + for (int i = 0; i < 3; i++) { + for (int j = 0; j < 3; j++) { + double x = _camera_matrix.at(i, j); intrinsic_list1D.push_back(x); } } return intrinsic_list1D; } + +CameraParams& CameraParams::operator=(const CameraParams& other) { + if (this != &other) { + // Copy members from 'other' to 'this' + this->_camera_matrix = other._camera_matrix.clone(); + this->_dist_coeff = other._dist_coeff.clone(); + this->_image_size = other._image_size; + } + return *this; +} ////////////// SERIALIZATION ////////////// void CameraParams::readFromFileNode(const cv::FileNode& file_node) { @@ -99,7 +109,8 @@ void CameraParams::writeToFileStorage(cv::FileStorage& file_storage) const { file_storage << "}"; } -void read(const cv::FileNode& node, cam::CameraParams& params, const cam::CameraParams& default_value) { +void read(const cv::FileNode& node, cam::CameraParams& params, + const cam::CameraParams& default_value) { if (node.empty()) { params = default_value; } else { @@ -107,7 +118,8 @@ void read(const cv::FileNode& node, cam::CameraParams& params, const cam::Camera } } -void write(cv::FileStorage& fs, const std::string& name, const cam::CameraParams& params) { +void write(cv::FileStorage& fs, [[maybe_unused]] const std::string& name, + const cam::CameraParams& params) { params.writeToFileStorage(fs); } diff --git a/src/camera/CameraParams.h b/src/camera/CameraParams.h index 82eb37221..73b6dedeb 100644 --- a/src/camera/CameraParams.h +++ b/src/camera/CameraParams.h @@ -1,8 +1,9 @@ #pragma once -#include #include +#include + namespace cam { /** @@ -112,6 +113,12 @@ class CameraParams { @brief Gets the camera intrinsics as a 1d list. */ std::vector getIntrinsicList(); + + /** + @brief Define a copy assignment operator + */ + CameraParams& operator=(const CameraParams& other); + /** @brief Reads the data for this CameraParams object from the given cv::FileNode object. @@ -147,6 +154,6 @@ void write(cv::FileStorage& fs, const std::string& name, const CameraParams& par /** @} */ -} +} // namespace cam // namespace cam diff --git a/src/network/MissionControlProtocol.cpp b/src/network/MissionControlProtocol.cpp index ab7f450cb..9d5b02a98 100644 --- a/src/network/MissionControlProtocol.cpp +++ b/src/network/MissionControlProtocol.cpp @@ -225,11 +225,11 @@ static bool validateJointPositionRequest(const json& j) { return validateJoint(j) && util::validateKey(j, "position", val_t::number_integer); } -static void handleJointPositionRequest(const json& j) { +static void handleJointPositionRequest([[maybe_unused]] const json& j) { // TODO: ignore this message if we are in autonomous mode. - std::string motor = j["joint"]; - double position_deg = j["position"]; - int32_t position_mdeg = std::round(position_deg * 1000); + // std::string motor = j["joint"]; + // double position_deg = j["position"]; + // int32_t position_mdeg = std::round(position_deg * 1000); // TODO: actually implement joint position requests // setMotorPos(motor, position_mdeg); }