From b42fa30cf0c153ea71b9b4e8bf29aad4a974275e Mon Sep 17 00:00:00 2001 From: Maximilian Schmeller Date: Mon, 27 Nov 2023 17:37:52 +0900 Subject: [PATCH] =?UTF-8?q?Fix=20unused=20parameter=20=E2=80=98sensor=5Fco?= =?UTF-8?q?nfiguration=E2=80=99=20warning=20for=20Velodyne?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../velodyne_hw_interface.hpp | 7 ++++--- .../velodyne_hw_interface.cpp | 20 ++++++++++++------- 2 files changed, 17 insertions(+), 10 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp index 11126d69e..6256c5e2b 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp @@ -11,11 +11,11 @@ #if (BOOST_VERSION / 100 == 1074) // Boost 1.74 #define BOOST_ALLOW_DEPRECATED_HEADERS #endif +#include "boost_tcp_driver/http_client_driver.hpp" +#include "boost_udp_driver/udp_driver.hpp" #include "nebula_common/velodyne/velodyne_common.hpp" #include "nebula_common/velodyne/velodyne_status.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp" -#include "boost_tcp_driver/http_client_driver.hpp" -#include "boost_udp_driver/udp_driver.hpp" #include @@ -243,7 +243,8 @@ class VelodyneHwInterface : NebulaHwInterfaceBase VelodyneStatus GetSnapshotAsync(); /// @brief Checking the current settings and changing the difference point /// @return Resulting status - VelodyneStatus CheckAndSetConfigBySnapshotAsync(); + VelodyneStatus CheckAndSetConfigBySnapshotAsync( + std::shared_ptr sensor_configuration); /// @brief Setting Motor RPM (async) /// @param rpm the RPM of the motor /// @return Resulting status diff --git a/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp index 35aeeec82..6bc174660 100644 --- a/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp @@ -29,7 +29,9 @@ Status VelodyneHwInterface::InitializeSensorConfiguration( Status VelodyneHwInterface::SetSensorConfiguration( std::shared_ptr sensor_configuration) { - VelodyneStatus status = CheckAndSetConfigBySnapshotAsync(); + auto velodyne_sensor_configuration = + std::static_pointer_cast(sensor_configuration); + VelodyneStatus status = CheckAndSetConfigBySnapshotAsync(velodyne_sensor_configuration); Status rt = status; return rt; } @@ -99,7 +101,10 @@ void VelodyneHwInterface::ReceiveCloudPacketCallback(const std::vector } prev_packet_first_azm_phased_ = packet_first_azm_phased_; } -Status VelodyneHwInterface::CloudInterfaceStop() { return Status::ERROR_1; } +Status VelodyneHwInterface::CloudInterfaceStop() +{ + return Status::ERROR_1; +} Status VelodyneHwInterface::GetSensorConfiguration(SensorConfigurationBase & sensor_configuration) { @@ -222,8 +227,7 @@ VelodyneStatus VelodyneHwInterface::CheckAndSetConfig( SetFovStartAsync(setting_cloud_min_angle); std::cout << "VelodyneHwInterface::parse_json(" << target_key << "): " << current_cloud_min_angle << std::endl; - std::cout << "sensor_configuration->cloud_min_angle: " << setting_cloud_min_angle - << std::endl; + std::cout << "sensor_configuration->cloud_min_angle: " << setting_cloud_min_angle << std::endl; } target_key = "config.fov.end"; @@ -237,8 +241,7 @@ VelodyneStatus VelodyneHwInterface::CheckAndSetConfig( SetFovEndAsync(setting_cloud_max_angle); std::cout << "VelodyneHwInterface::parse_json(" << target_key << "): " << current_cloud_max_angle << std::endl; - std::cout << "sensor_configuration->cloud_max_angle: " << setting_cloud_max_angle - << std::endl; + std::cout << "sensor_configuration->cloud_max_angle: " << setting_cloud_max_angle << std::endl; } target_key = "config.host.addr"; @@ -521,8 +524,11 @@ VelodyneStatus VelodyneHwInterface::GetSnapshotAsync() return GetSnapshotAsync([this](const std::string & str) { ParseJson(str); }); } -VelodyneStatus VelodyneHwInterface::CheckAndSetConfigBySnapshotAsync() +VelodyneStatus VelodyneHwInterface::CheckAndSetConfigBySnapshotAsync( + std::shared_ptr sensor_configuration) { + sensor_configuration_ = sensor_configuration; + return GetSnapshotAsync([this](const std::string & str) { auto tree = ParseJson(str); std::cout << "ParseJson OK\n";