From 37724a0b727ae3f4689ebd06a7c39e750d75d997 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 31 Jan 2025 10:28:30 +0900 Subject: [PATCH] chore(nebula_ros): replace non-standard stringstream usage with nebula::util::to_string Fixes #254. Signed-off-by: Max SCHMELLER --- .../continental_ars548_decoder_wrapper.cpp | 5 +++-- .../continental_ars548_hw_interface_wrapper.cpp | 13 +++++++------ .../continental/continental_ars548_ros_wrapper.cpp | 7 ++++--- .../continental_srr520_decoder_wrapper.cpp | 5 +++-- .../continental_srr520_hw_interface_wrapper.cpp | 7 ++++--- .../continental/continental_srr520_ros_wrapper.cpp | 7 ++++--- nebula_ros/src/hesai/decoder_wrapper.cpp | 4 ++-- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 11 +++++------ nebula_ros/src/hesai/hw_interface_wrapper.cpp | 4 ++-- nebula_ros/src/robosense/hw_interface_wrapper.cpp | 5 +++-- nebula_ros/src/robosense/robosense_ros_wrapper.cpp | 6 +++--- nebula_ros/src/velodyne/decoder_wrapper.cpp | 12 +++++------- nebula_ros/src/velodyne/hw_interface_wrapper.cpp | 11 +++++------ nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp | 7 ++++--- 14 files changed, 54 insertions(+), 50 deletions(-) diff --git a/nebula_ros/src/continental/continental_ars548_decoder_wrapper.cpp b/nebula_ros/src/continental/continental_ars548_decoder_wrapper.cpp index a02d58cce..6e22d67de 100644 --- a/nebula_ros/src/continental/continental_ars548_decoder_wrapper.cpp +++ b/nebula_ros/src/continental/continental_ars548_decoder_wrapper.cpp @@ -14,6 +14,8 @@ #include "nebula_ros/continental/continental_ars548_decoder_wrapper.hpp" +#include + #include namespace nebula::ros @@ -39,8 +41,7 @@ ContinentalARS548DecoderWrapper::ContinentalARS548DecoderWrapper( status_ = driver_ptr_->get_status(); if (Status::OK != status_) { - throw std::runtime_error( - (std::stringstream() << "Error instantiating decoder: " << status_).str()); + throw std::runtime_error("Error instantiating decoder: " + util::to_string(status_)); } // Publish packets only if HW interface is connected diff --git a/nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp b/nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp index 79e293347..fa6e45616 100644 --- a/nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp +++ b/nebula_ros/src/continental/continental_ars548_hw_interface_wrapper.cpp @@ -14,6 +14,8 @@ #include "nebula_ros/continental/continental_ars548_hw_interface_wrapper.hpp" +#include + #include #include @@ -36,8 +38,7 @@ ContinentalARS548HwInterfaceWrapper::ContinentalARS548HwInterfaceWrapper( status_ = hw_interface_->set_sensor_configuration(config_ptr); if (status_ != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Could not initialize HW interface: " << status_).str()); + throw std::runtime_error("Could not initialize HW interface: " + util::to_string(status_)); } status_ = Status::OK; @@ -166,7 +167,7 @@ void ContinentalARS548HwInterfaceWrapper::set_network_configuration_request_call { auto result = hw_interface_->set_sensor_ip_address(request->sensor_ip.data); response->success = result == Status::OK; - response->message = (std::stringstream() << result).str(); + response->message = util::to_string(result); } void ContinentalARS548HwInterfaceWrapper::set_sensor_mounting_request_callback( @@ -230,7 +231,7 @@ void ContinentalARS548HwInterfaceWrapper::set_sensor_mounting_request_callback( longitudinal, lateral, vertical, yaw, pitch, request->plug_orientation); response->success = result == Status::OK; - response->message = (std::stringstream() << result).str(); + response->message = util::to_string(result); } void ContinentalARS548HwInterfaceWrapper::set_vehicle_parameters_request_callback( @@ -277,7 +278,7 @@ void ContinentalARS548HwInterfaceWrapper::set_vehicle_parameters_request_callbac vehicle_length, vehicle_width, vehicle_height, vehicle_wheelbase); response->success = result == Status::OK; - response->message = (std::stringstream() << result).str(); + response->message = util::to_string(result); } void ContinentalARS548HwInterfaceWrapper::set_radar_parameters_request_callback( @@ -291,7 +292,7 @@ void ContinentalARS548HwInterfaceWrapper::set_radar_parameters_request_callback( request->country_code, request->powersave_standstill); response->success = result == Status::OK; - response->message = (std::stringstream() << result).str(); + response->message = util::to_string(result); } } // namespace nebula::ros diff --git a/nebula_ros/src/continental/continental_ars548_ros_wrapper.cpp b/nebula_ros/src/continental/continental_ars548_ros_wrapper.cpp index f459c208f..d3cce0911 100644 --- a/nebula_ros/src/continental/continental_ars548_ros_wrapper.cpp +++ b/nebula_ros/src/continental/continental_ars548_ros_wrapper.cpp @@ -14,6 +14,8 @@ #include "nebula_ros/continental/continental_ars548_ros_wrapper.hpp" +#include + #pragma clang diagnostic ignored "-Wbitwise-instead-of-logical" namespace nebula::ros @@ -31,8 +33,7 @@ ContinentalARS548RosWrapper::ContinentalARS548RosWrapper(const rclcpp::NodeOptio wrapper_status_ = declare_and_get_sensor_config_params(); if (wrapper_status_ != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str()); + throw std::runtime_error("Sensor configuration invalid: " + util::to_string(wrapper_status_)); } RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *config_ptr_); @@ -222,7 +223,7 @@ rcl_interfaces::msg::SetParametersResult ContinentalARS548RosWrapper::on_paramet RCLCPP_WARN_STREAM(get_logger(), "OnParameterChange aborted: " << status); auto result = SetParametersResult(); result.successful = false; - result.reason = (std::stringstream() << "Invalid configuration: " << status).str(); + result.reason = "Invalid configuration: " + util::to_string(status); return result; } diff --git a/nebula_ros/src/continental/continental_srr520_decoder_wrapper.cpp b/nebula_ros/src/continental/continental_srr520_decoder_wrapper.cpp index f4bbbc113..7d433e4f1 100644 --- a/nebula_ros/src/continental/continental_srr520_decoder_wrapper.cpp +++ b/nebula_ros/src/continental/continental_srr520_decoder_wrapper.cpp @@ -14,6 +14,8 @@ #include "nebula_ros/continental/continental_srr520_decoder_wrapper.hpp" +#include + #include namespace nebula::ros @@ -41,8 +43,7 @@ ContinentalSRR520DecoderWrapper::ContinentalSRR520DecoderWrapper( status_ = driver_ptr_->get_status(); if (Status::OK != status_) { - throw std::runtime_error( - (std::stringstream() << "Error instantiating decoder: " << status_).str()); + throw std::runtime_error("Error instantiating decoder: " + util::to_string(status_)); } // Publish packets only if HW interface is connected diff --git a/nebula_ros/src/continental/continental_srr520_hw_interface_wrapper.cpp b/nebula_ros/src/continental/continental_srr520_hw_interface_wrapper.cpp index 80df6d84c..e0ef91ff0 100644 --- a/nebula_ros/src/continental/continental_srr520_hw_interface_wrapper.cpp +++ b/nebula_ros/src/continental/continental_srr520_hw_interface_wrapper.cpp @@ -14,6 +14,8 @@ #include "nebula_ros/continental/continental_srr520_hw_interface_wrapper.hpp" +#include + #include #include @@ -36,8 +38,7 @@ ContinentalSRR520HwInterfaceWrapper::ContinentalSRR520HwInterfaceWrapper( status_ = hw_interface_->set_sensor_configuration(config_ptr_); if (status_ != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Could not initialize HW interface: " << status_).str()); + throw std::runtime_error("Could not initialize HW interface: " + util::to_string(status_)); } status_ = Status::OK; @@ -170,7 +171,7 @@ void ContinentalSRR520HwInterfaceWrapper::configure_sensor_request_callback( request->plug_bottom, request->reset_sensor_configuration); response->success = result == Status::OK; - response->message = (std::stringstream() << result).str(); + response->message = util::to_string(result); } void ContinentalSRR520HwInterfaceWrapper::sync_timer_callback() diff --git a/nebula_ros/src/continental/continental_srr520_ros_wrapper.cpp b/nebula_ros/src/continental/continental_srr520_ros_wrapper.cpp index 6ec611e42..06fd7d6e3 100644 --- a/nebula_ros/src/continental/continental_srr520_ros_wrapper.cpp +++ b/nebula_ros/src/continental/continental_srr520_ros_wrapper.cpp @@ -14,6 +14,8 @@ #include "nebula_ros/continental/continental_srr520_ros_wrapper.hpp" +#include + #pragma clang diagnostic ignored "-Wbitwise-instead-of-logical" namespace nebula::ros @@ -31,8 +33,7 @@ ContinentalSRR520RosWrapper::ContinentalSRR520RosWrapper(const rclcpp::NodeOptio wrapper_status_ = declare_and_get_sensor_config_params(); if (wrapper_status_ != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str()); + throw std::runtime_error("Sensor configuration invalid: " + util::to_string(wrapper_status_)); } RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *config_ptr_); @@ -207,7 +208,7 @@ rcl_interfaces::msg::SetParametersResult ContinentalSRR520RosWrapper::on_paramet RCLCPP_WARN_STREAM(get_logger(), "OnParameterChange aborted: " << status); auto result = SetParametersResult(); result.successful = false; - result.reason = (std::stringstream() << "Invalid configuration: " << status).str(); + result.reason = "Invalid configuration: " + util::to_string(status); return result; } diff --git a/nebula_ros/src/hesai/decoder_wrapper.cpp b/nebula_ros/src/hesai/decoder_wrapper.cpp index e3d726fd9..bc086500e 100644 --- a/nebula_ros/src/hesai/decoder_wrapper.cpp +++ b/nebula_ros/src/hesai/decoder_wrapper.cpp @@ -3,6 +3,7 @@ #include "nebula_ros/hesai/decoder_wrapper.hpp" #include +#include #include #include @@ -42,8 +43,7 @@ HesaiDecoderWrapper::HesaiDecoderWrapper( status_ = driver_ptr_->get_status(); if (Status::OK != status_) { - throw std::runtime_error( - (std::stringstream() << "Error instantiating decoder: " << status_).str()); + throw std::runtime_error("Error instantiating decoder: " + util::to_string(status_)); } // Publish packets only if enabled by the ROS wrapper diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 387d6c4c7..960db3aa2 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -6,6 +6,7 @@ #include #include +#include #include #include @@ -32,8 +33,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) wrapper_status_ = declare_and_get_sensor_config_params(); if (wrapper_status_ != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str()); + throw std::runtime_error("Sensor configuration invalid: " + util::to_string(wrapper_status_)); } RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *sensor_cfg_ptr_); @@ -61,7 +61,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) get_calibration_data(sensor_cfg_ptr_->calibration_path, force_load_caibration_from_file); if (!calibration_result.has_value()) { throw std::runtime_error( - (std::stringstream() << "No valid calibration found: " << calibration_result.error()).str()); + "No valid calibration found: " + util::to_string(calibration_result.error())); } bool lidar_range_supported = @@ -72,8 +72,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) auto status = hw_interface_wrapper_->hw_interface()->check_and_set_lidar_range(*calibration_result.value()); if (status != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Could not set sensor FoV: " << status).str()); + throw std::runtime_error("Could not set sensor FoV: " + util::to_string(status)); } } @@ -387,7 +386,7 @@ rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::on_parameter_change( RCLCPP_WARN_STREAM(get_logger(), "OnParameterChange aborted: " << status); auto result = SetParametersResult(); result.successful = false; - result.reason = (std::stringstream() << "Invalid configuration: " << status).str(); + result.reason = "Invalid configuration: " + util::to_string(status); return result; } diff --git a/nebula_ros/src/hesai/hw_interface_wrapper.cpp b/nebula_ros/src/hesai/hw_interface_wrapper.cpp index d66ad0eff..69f09cee9 100644 --- a/nebula_ros/src/hesai/hw_interface_wrapper.cpp +++ b/nebula_ros/src/hesai/hw_interface_wrapper.cpp @@ -5,6 +5,7 @@ #include "nebula_ros/common/parameter_descriptors.hpp" #include "nebula_ros/common/rclcpp_logger.hpp" +#include #include #include @@ -28,8 +29,7 @@ HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper( std::static_pointer_cast(config)); if (status_ != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Could not initialize HW interface: " << status_).str()); + throw std::runtime_error("Could not initialize HW interface: " + util::to_string(status_)); } hw_interface_->set_target_model(config->sensor_model); diff --git a/nebula_ros/src/robosense/hw_interface_wrapper.cpp b/nebula_ros/src/robosense/hw_interface_wrapper.cpp index 545031a99..71b653da1 100644 --- a/nebula_ros/src/robosense/hw_interface_wrapper.cpp +++ b/nebula_ros/src/robosense/hw_interface_wrapper.cpp @@ -2,6 +2,8 @@ #include "nebula_ros/robosense/hw_interface_wrapper.hpp" +#include + namespace nebula::ros { RobosenseHwInterfaceWrapper::RobosenseHwInterfaceWrapper( @@ -16,8 +18,7 @@ RobosenseHwInterfaceWrapper::RobosenseHwInterfaceWrapper( status_ = hw_interface_->set_sensor_configuration(config); if (Status::OK != status_) { - throw std::runtime_error( - (std::stringstream{} << "Sensor configuration invalid: " << status_).str()); + throw std::runtime_error("Sensor configuration invalid: " + util::to_string(status_)); } } diff --git a/nebula_ros/src/robosense/robosense_ros_wrapper.cpp b/nebula_ros/src/robosense/robosense_ros_wrapper.cpp index 85d34bac9..d12dfb82b 100644 --- a/nebula_ros/src/robosense/robosense_ros_wrapper.cpp +++ b/nebula_ros/src/robosense/robosense_ros_wrapper.cpp @@ -4,6 +4,7 @@ #include "nebula_ros/common/parameter_descriptors.hpp" +#include #include #include @@ -26,8 +27,7 @@ RobosenseRosWrapper::RobosenseRosWrapper(const rclcpp::NodeOptions & options) wrapper_status_ = declare_and_get_sensor_config_params(); if (wrapper_status_ != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str()); + throw std::runtime_error("Sensor configuration invalid: " + util::to_string(wrapper_status_)); } RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *sensor_cfg_ptr_); @@ -285,7 +285,7 @@ rcl_interfaces::msg::SetParametersResult RobosenseRosWrapper::on_parameter_chang RCLCPP_WARN_STREAM(get_logger(), "OnParameterChange aborted: " << status); auto result = SetParametersResult(); result.successful = false; - result.reason = (std::stringstream() << "Invalid configuration: " << status).str(); + result.reason = "Invalid configuration: " + util::to_string(status); return result; } diff --git a/nebula_ros/src/velodyne/decoder_wrapper.cpp b/nebula_ros/src/velodyne/decoder_wrapper.cpp index 69b046676..cf9990656 100644 --- a/nebula_ros/src/velodyne/decoder_wrapper.cpp +++ b/nebula_ros/src/velodyne/decoder_wrapper.cpp @@ -2,6 +2,7 @@ #include "nebula_ros/velodyne/decoder_wrapper.hpp" +#include #include namespace nebula::ros @@ -29,7 +30,7 @@ VelodyneDecoderWrapper::VelodyneDecoderWrapper( if (!calibration_result.has_value()) { throw std::runtime_error( - (std::stringstream() << "No valid calibration found: " << calibration_result.error()).str()); + "No valid calibration found: " + util::to_string(calibration_result.error())); } calibration_cfg_ptr_ = calibration_result.value(); @@ -42,8 +43,7 @@ VelodyneDecoderWrapper::VelodyneDecoderWrapper( status_ = driver_ptr_->get_status(); if (Status::OK != status_) { - throw std::runtime_error( - (std::stringstream() << "Error instantiating decoder: " << status_).str()); + throw std::runtime_error("Error instantiating decoder: " + util::to_string(status_)); } // Publish packets only if HW interface is connected @@ -117,10 +117,8 @@ rcl_interfaces::msg::SetParametersResult VelodyneDecoderWrapper::on_parameter_ch if (!get_calibration_result.has_value()) { auto result = SetParametersResult(); result.successful = false; - result.reason = - (std::stringstream() << "Could not change calibration file to '" << calibration_path - << "': " << get_calibration_result.error()) - .str(); + result.reason = "Could not change calibration file to '" + calibration_path + + "': " + util::to_string(get_calibration_result.error()); return result; } diff --git a/nebula_ros/src/velodyne/hw_interface_wrapper.cpp b/nebula_ros/src/velodyne/hw_interface_wrapper.cpp index 338f2ab3e..8577cef8e 100644 --- a/nebula_ros/src/velodyne/hw_interface_wrapper.cpp +++ b/nebula_ros/src/velodyne/hw_interface_wrapper.cpp @@ -2,6 +2,8 @@ #include "nebula_ros/velodyne/hw_interface_wrapper.hpp" +#include + namespace nebula::ros { @@ -20,8 +22,7 @@ VelodyneHwInterfaceWrapper::VelodyneHwInterfaceWrapper( status_ = hw_interface_->initialize_sensor_configuration(config); if (status_ != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Could not initialize HW interface: " << status_).str()); + throw std::runtime_error("Could not initialize HW interface: " + util::to_string(status_)); } if (use_udp_only_) { @@ -32,8 +33,7 @@ VelodyneHwInterfaceWrapper::VelodyneHwInterfaceWrapper( status_ = hw_interface_->init_http_client(); if (status_ != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Could not initialize HTTP client: " << status_).str()); + throw std::runtime_error("Could not initialize HTTP client: " + util::to_string(status_)); } if (setup_sensor_) { @@ -42,8 +42,7 @@ VelodyneHwInterfaceWrapper::VelodyneHwInterfaceWrapper( } if (status_ != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Could not set sensor configuration: " << status_).str()); + throw std::runtime_error("Could not set sensor configuration: " + util::to_string(status_)); } status_ = Status::OK; diff --git a/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp b/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp index e06535766..55b67e923 100644 --- a/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp +++ b/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp @@ -2,6 +2,8 @@ #include "nebula_ros/velodyne/velodyne_ros_wrapper.hpp" +#include + #pragma clang diagnostic ignored "-Wbitwise-instead-of-logical" namespace nebula::ros @@ -20,8 +22,7 @@ VelodyneRosWrapper::VelodyneRosWrapper(const rclcpp::NodeOptions & options) wrapper_status_ = declare_and_get_sensor_config_params(); if (wrapper_status_ != Status::OK) { - throw std::runtime_error( - (std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str()); + throw std::runtime_error("Sensor configuration invalid: " + util::to_string(wrapper_status_)); } RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *sensor_cfg_ptr_); @@ -233,7 +234,7 @@ rcl_interfaces::msg::SetParametersResult VelodyneRosWrapper::on_parameter_change RCLCPP_WARN_STREAM(get_logger(), "OnParameterChange aborted: " << status); auto result = SetParametersResult(); result.successful = false; - result.reason = (std::stringstream() << "Invalid configuration: " << status).str(); + result.reason = "Invalid configuration: " + util::to_string(status); return result; }