diff --git a/localization/vehicle_velocity_converter/CMakeLists.txt b/localization/vehicle_velocity_converter/CMakeLists.txt index e2c108c244538..b63c8f42be84a 100644 --- a/localization/vehicle_velocity_converter/CMakeLists.txt +++ b/localization/vehicle_velocity_converter/CMakeLists.txt @@ -8,8 +8,7 @@ if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_EXTENSIONS OFF) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - # add_compile_options(-Wall -Wextra -Wpedantic) - add_compile_options(-Wno-unused-parameter) + add_compile_options(-Wall -Wextra -Wpedantic -Werror) endif() # find dependencies diff --git a/localization/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp b/localization/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp index 997b98a6bbcf4..d4cc91a2b0ae9 100644 --- a/localization/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp +++ b/localization/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp @@ -17,8 +17,7 @@ VehicleVelocityConverter::VehicleVelocityConverter() : Node("vehicle_velocity_converter") { // set covariance value for twist with covariance msg - declare_parameter("twist_covariance"); - std::vector covariance = get_parameter("twist_covariance").as_double_array(); + std::vector covariance = declare_parameter>("twist_covariance"); for (std::size_t i = 0; i < covariance.size(); ++i) { twist_covariance_[i] = covariance[i]; }