Skip to content

Commit

Permalink
chore(nebula_ros): replace non-standard stringstream usage with nebul…
Browse files Browse the repository at this point in the history
…a::util::to_string

Fixes #254.

Signed-off-by: Max SCHMELLER <max.schmeller@tier4.jp>
  • Loading branch information
mojomex committed Jan 31, 2025
1 parent 33e77cf commit 37724a0
Show file tree
Hide file tree
Showing 14 changed files with 54 additions and 50 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "nebula_ros/continental/continental_ars548_decoder_wrapper.hpp"

#include <nebula_common/util/string_conversions.hpp>

#include <pcl_conversions/pcl_conversions.h>

namespace nebula::ros
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "nebula_ros/continental/continental_ars548_hw_interface_wrapper.hpp"

#include <nebula_common/util/string_conversions.hpp>

#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

Expand All @@ -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;
Expand Down Expand Up @@ -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(
Expand Down Expand Up @@ -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(
Expand Down Expand Up @@ -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(
Expand All @@ -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
7 changes: 4 additions & 3 deletions nebula_ros/src/continental/continental_ars548_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "nebula_ros/continental/continental_ars548_ros_wrapper.hpp"

#include <nebula_common/util/string_conversions.hpp>

#pragma clang diagnostic ignored "-Wbitwise-instead-of-logical"

namespace nebula::ros
Expand All @@ -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_);
Expand Down Expand Up @@ -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;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "nebula_ros/continental/continental_srr520_decoder_wrapper.hpp"

#include <nebula_common/util/string_conversions.hpp>

#include <pcl_conversions/pcl_conversions.h>

namespace nebula::ros
Expand Down Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "nebula_ros/continental/continental_srr520_hw_interface_wrapper.hpp"

#include <nebula_common/util/string_conversions.hpp>

#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

Expand All @@ -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;
Expand Down Expand Up @@ -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()
Expand Down
7 changes: 4 additions & 3 deletions nebula_ros/src/continental/continental_srr520_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "nebula_ros/continental/continental_srr520_ros_wrapper.hpp"

#include <nebula_common/util/string_conversions.hpp>

#pragma clang diagnostic ignored "-Wbitwise-instead-of-logical"

namespace nebula::ros
Expand All @@ -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_);
Expand Down Expand Up @@ -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;
}

Expand Down
4 changes: 2 additions & 2 deletions nebula_ros/src/hesai/decoder_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include "nebula_ros/hesai/decoder_wrapper.hpp"

#include <nebula_common/hesai/hesai_common.hpp>
#include <nebula_common/util/string_conversions.hpp>
#include <rclcpp/logging.hpp>
#include <rclcpp/time.hpp>

Expand Down Expand Up @@ -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
Expand Down
11 changes: 5 additions & 6 deletions nebula_ros/src/hesai/hesai_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

#include <nebula_common/hesai/hesai_common.hpp>
#include <nebula_common/nebula_common.hpp>
#include <nebula_common/util/string_conversions.hpp>
#include <nebula_decoders/nebula_decoders_common/angles.hpp>

#include <cstdint>
Expand All @@ -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_);
Expand Down Expand Up @@ -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 =
Expand All @@ -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));
}
}

Expand Down Expand Up @@ -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;
}

Expand Down
4 changes: 2 additions & 2 deletions nebula_ros/src/hesai/hw_interface_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include "nebula_ros/common/parameter_descriptors.hpp"
#include "nebula_ros/common/rclcpp_logger.hpp"

#include <nebula_common/util/string_conversions.hpp>
#include <nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp>

#include <memory>
Expand All @@ -28,8 +29,7 @@ HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(
std::static_pointer_cast<const drivers::SensorConfigurationBase>(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);
Expand Down
5 changes: 3 additions & 2 deletions nebula_ros/src/robosense/hw_interface_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

#include "nebula_ros/robosense/hw_interface_wrapper.hpp"

#include <nebula_common/util/string_conversions.hpp>

namespace nebula::ros
{
RobosenseHwInterfaceWrapper::RobosenseHwInterfaceWrapper(
Expand All @@ -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_));
}
}

Expand Down
6 changes: 3 additions & 3 deletions nebula_ros/src/robosense/robosense_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

#include "nebula_ros/common/parameter_descriptors.hpp"

#include <nebula_common/util/string_conversions.hpp>
#include <rclcpp/qos.hpp>

#include <robosense_msgs/msg/detail/robosense_info_packet__struct.hpp>
Expand All @@ -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_);
Expand Down Expand Up @@ -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;
}

Expand Down
12 changes: 5 additions & 7 deletions nebula_ros/src/velodyne/decoder_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include "nebula_ros/velodyne/decoder_wrapper.hpp"

#include <nebula_common/util/string_conversions.hpp>
#include <rclcpp/time.hpp>

namespace nebula::ros
Expand Down Expand Up @@ -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();
Expand All @@ -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
Expand Down Expand Up @@ -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;
}

Expand Down
11 changes: 5 additions & 6 deletions nebula_ros/src/velodyne/hw_interface_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

#include "nebula_ros/velodyne/hw_interface_wrapper.hpp"

#include <nebula_common/util/string_conversions.hpp>

namespace nebula::ros
{

Expand All @@ -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_) {
Expand All @@ -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_) {
Expand All @@ -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;
Expand Down
Loading

0 comments on commit 37724a0

Please sign in to comment.