Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix: get rid of "unused parameter ‘sensor_configuration’" warning for Velodyne #99

Merged
merged 1 commit into from
Dec 5, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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 <rclcpp/rclcpp.hpp>

Expand Down Expand Up @@ -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<VelodyneSensorConfiguration> sensor_configuration);
/// @brief Setting Motor RPM (async)
/// @param rpm the RPM of the motor
/// @return Resulting status
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,9 @@ Status VelodyneHwInterface::InitializeSensorConfiguration(
Status VelodyneHwInterface::SetSensorConfiguration(
std::shared_ptr<SensorConfigurationBase> sensor_configuration)
{
VelodyneStatus status = CheckAndSetConfigBySnapshotAsync();
auto velodyne_sensor_configuration =
std::static_pointer_cast<VelodyneSensorConfiguration>(sensor_configuration);
VelodyneStatus status = CheckAndSetConfigBySnapshotAsync(velodyne_sensor_configuration);
Status rt = status;
return rt;
}
Expand Down Expand Up @@ -99,7 +101,10 @@ void VelodyneHwInterface::ReceiveCloudPacketCallback(const std::vector<uint8_t>
}
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)
{
Expand Down Expand Up @@ -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";
Expand All @@ -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";
Expand Down Expand Up @@ -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<VelodyneSensorConfiguration> sensor_configuration)
{
sensor_configuration_ = sensor_configuration;

return GetSnapshotAsync([this](const std::string & str) {
auto tree = ParseJson(str);
std::cout << "ParseJson OK\n";
Expand Down
Loading