Skip to content

Commit

Permalink
chore: make config field names more readable when pretty-printing
Browse files Browse the repository at this point in the history
  • Loading branch information
mojomex committed Jul 5, 2024
1 parent 0f4570f commit 7f8db71
Show file tree
Hide file tree
Showing 21 changed files with 60 additions and 60 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -55,18 +55,18 @@ struct ContinentalARS548SensorConfiguration : EthernetSensorConfigurationBase
inline std::ostream & operator<<(
std::ostream & os, ContinentalARS548SensorConfiguration const & arg)
{
os << "ContinentalARS548SensorConfiguration:" << '\n';
os << "Continental ARS548 Sensor Configuration:" << '\n';
os << (EthernetSensorConfigurationBase)(arg) << '\n';
os << "MulticastIP: " << arg.multicast_ip << '\n';
os << "BaseFrame: " << arg.base_frame << '\n';
os << "ObjectFrame: " << arg.object_frame << '\n';
os << "ConfigurationHostPort: " << arg.configuration_host_port << '\n';
os << "ConfigurationSensorPort: " << arg.configuration_sensor_port << '\n';
os << "UseSensorTime: " << arg.use_sensor_time << '\n';
os << "ConfigurationVehicleLength: " << arg.configuration_vehicle_length << '\n';
os << "ConfigurationVehicleWidth: " << arg.configuration_vehicle_width << '\n';
os << "ConfigurationVehicleHeight: " << arg.configuration_vehicle_height << '\n';
os << "ConfigurationVehicleWheelbase: " << arg.configuration_vehicle_wheelbase;
os << "Multicast IP: " << arg.multicast_ip << '\n';
os << "Base Frame: " << arg.base_frame << '\n';
os << "Object Frame: " << arg.object_frame << '\n';
os << "Host Port: " << arg.configuration_host_port << '\n';
os << "Sensor Port: " << arg.configuration_sensor_port << '\n';
os << "UseSensor Time: " << arg.use_sensor_time << '\n';
os << "Vehicle Length: " << arg.configuration_vehicle_length << '\n';
os << "Vehicle Width: " << arg.configuration_vehicle_width << '\n';
os << "Vehicle Height: " << arg.configuration_vehicle_height << '\n';
os << "Vehicle Wheelbase: " << arg.configuration_vehicle_wheelbase;
return os;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,11 +50,11 @@ struct ContinentalSRR520SensorConfiguration : CANSensorConfigurationBase
inline std::ostream & operator<<(
std::ostream & os, ContinentalSRR520SensorConfiguration const & arg)
{
os << "ContinentalSRR520SensorConfiguration:" << '\n';
os << "Continental SRR520 Sensor Configuration:" << '\n';
os << (CANSensorConfigurationBase)(arg) << '\n';
os << "BaseFrame: " << arg.base_frame << '\n';
os << "SyncUseBusTime: " << arg.sync_use_bus_time << '\n';
os << "ConfigurationVehicleWheelbase: " << arg.configuration_vehicle_wheelbase;
os << "Base Frame: " << arg.base_frame << '\n';
os << "Sync Use Bus Time: " << arg.sync_use_bus_time << '\n';
os << "Vehicle Wheelbase: " << arg.configuration_vehicle_wheelbase;
return os;
}

Expand Down
22 changes: 11 additions & 11 deletions nebula_common/include/nebula_common/hesai/hesai_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,18 +50,18 @@ struct HesaiSensorConfiguration : public LidarConfigurationBase
/// @return stream
inline std::ostream & operator<<(std::ostream & os, HesaiSensorConfiguration const & arg)
{
os << "HesaiSensorConfiguration:" << '\n';
os << "Hesai Sensor Configuration:" << '\n';
os << (LidarConfigurationBase)(arg) << '\n';
os << "GnssPort: " << arg.gnss_port << '\n';
os << "ScanPhase: " << arg.scan_phase << '\n';
os << "RotationSpeed: " << arg.rotation_speed << '\n';
os << "FOV(Start): " << arg.cloud_min_angle << '\n';
os << "FOV(End): " << arg.cloud_max_angle << '\n';
os << "DualReturnDistanceThreshold: " << arg.dual_return_distance_threshold << '\n';
os << "PtpProfile: " << arg.ptp_profile << '\n';
os << "PtpDomain: " << std::to_string(arg.ptp_domain) << '\n';
os << "PtpTransportType: " << arg.ptp_transport_type << '\n';
os << "PtpSwitchType: " << arg.ptp_switch_type;
os << "GNSS Port: " << arg.gnss_port << '\n';
os << "Scan Phase: " << arg.scan_phase << '\n';
os << "Rotation Speed: " << arg.rotation_speed << '\n';
os << "FoV Start: " << arg.cloud_min_angle << '\n';
os << "FoV End: " << arg.cloud_max_angle << '\n';
os << "Dual Return Distance Threshold: " << arg.dual_return_distance_threshold << '\n';
os << "PTP Profile: " << arg.ptp_profile << '\n';
os << "PTP Domain: " << std::to_string(arg.ptp_domain) << '\n';
os << "PTP Transport Type: " << arg.ptp_transport_type << '\n';
os << "PTP Switch Type: " << arg.ptp_switch_type;
return os;
}

Expand Down
20 changes: 10 additions & 10 deletions nebula_common/include/nebula_common/nebula_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -497,8 +497,8 @@ struct LidarConfigurationBase : EthernetSensorConfigurationBase
/// @return stream
inline std::ostream & operator<<(std::ostream & os, SensorConfigurationBase const & arg)
{
os << "SensorModel: " << arg.sensor_model << '\n';
os << "FrameID: " << arg.frame_id;
os << "Sensor Model: " << arg.sensor_model << '\n';
os << "Frame ID: " << arg.frame_id;
return os;
}

Expand All @@ -509,9 +509,9 @@ inline std::ostream & operator<<(std::ostream & os, SensorConfigurationBase cons
inline std::ostream & operator<<(std::ostream & os, EthernetSensorConfigurationBase const & arg)
{
os << (SensorConfigurationBase)(arg) << '\n';
os << "HostIP: " << arg.host_ip << '\n';
os << "SensorIP: " << arg.sensor_ip << '\n';
os << "DataPort: " << arg.data_port;
os << "Host IP: " << arg.host_ip << '\n';
os << "Sensor IP: " << arg.sensor_ip << '\n';
os << "Data Port: " << arg.data_port;
return os;
}

Expand All @@ -523,10 +523,10 @@ inline std::ostream & operator<<(std::ostream & os, CANSensorConfigurationBase c
{
os << (SensorConfigurationBase)(arg) << '\n';
os << "Interface: " << arg.interface << '\n';
os << "ReceiverTimeoutSec: " << arg.receiver_timeout_sec << '\n';
os << "SenderTimeoutSec: " << arg.sender_timeout_sec << '\n';
os << "Receiver Timeout (s): " << arg.receiver_timeout_sec << '\n';
os << "Sender Timeout (s): " << arg.sender_timeout_sec << '\n';
os << "Filters: " << arg.filters << '\n';
os << "UseBusTime: " << arg.use_bus_time;
os << "Use Bus Time: " << arg.use_bus_time;
return os;
}

Expand All @@ -538,10 +538,10 @@ inline std::ostream & operator<<(
std::ostream & os, nebula::drivers::LidarConfigurationBase const & arg)
{
os << (EthernetSensorConfigurationBase)(arg) << '\n';
os << "ReturnMode: " << arg.return_mode << '\n';
os << "Return Mode: " << arg.return_mode << '\n';
os << "Frequency: " << arg.frequency_ms << '\n';
os << "MTU: " << arg.packet_mtu_size << '\n';
os << "Use sensor time: " << arg.use_sensor_time;
os << "Use Sensor Time: " << arg.use_sensor_time;
return os;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,10 @@ struct RobosenseSensorConfiguration : LidarConfigurationBase
/// @return stream
inline std::ostream & operator<<(std::ostream & os, RobosenseSensorConfiguration const & arg)
{
os << "RobosenseSensorConfiguration:" << '\n';
os << "Robosense Sensor Configuration:" << '\n';
os << (LidarConfigurationBase)(arg) << '\n';
os << "GnssPort: " << arg.gnss_port << '\n';
os << "ScanPhase: " << arg.scan_phase;
os << "GNSS Port: " << arg.gnss_port << '\n';
os << "Scan Phase: " << arg.scan_phase;
return os;
}

Expand Down
12 changes: 6 additions & 6 deletions nebula_common/include/nebula_common/velodyne/velodyne_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,13 @@ struct VelodyneSensorConfiguration : LidarConfigurationBase
/// @return stream
inline std::ostream & operator<<(std::ostream & os, VelodyneSensorConfiguration const & arg)
{
os << "VelodyneSensorConfiguration:" << '\n';
os << "Velodyne Sensor Configuration:" << '\n';
os << (LidarConfigurationBase)(arg) << '\n';
os << "GnssPort: " << arg.gnss_port << '\n';
os << "ScanPhase: " << arg.scan_phase << '\n';
os << "RotationSpeed: " << arg.rotation_speed << '\n';
os << "FOV(Start): " << arg.cloud_min_angle << '\n';
os << "FOV(End): " << arg.cloud_max_angle;
os << "GNSS Port: " << arg.gnss_port << '\n';
os << "Scan Phase: " << arg.scan_phase << '\n';
os << "Rotation Speed: " << arg.rotation_speed << '\n';
os << "FoV Start: " << arg.cloud_min_angle << '\n';
os << "FoV End: " << arg.cloud_max_angle;
return os;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ Status HesaiRosOfflineExtractBag::GetParameters(
}
}

RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig: " << sensor_configuration);
RCLCPP_INFO_STREAM(this->get_logger(), "Sensor Configuration: " << sensor_configuration);
return Status::OK;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ Status HesaiRosOfflineExtractSample::GetParameters(
}
}

RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig: " << sensor_configuration);
RCLCPP_INFO_STREAM(this->get_logger(), "Sensor Configuration: " << sensor_configuration);
return Status::OK;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ ContinentalARS548RosWrapper::ContinentalARS548RosWrapper(const rclcpp::NodeOptio
(std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str());
}

RCLCPP_INFO_STREAM(get_logger(), "SensorConfig: " << *config_ptr_);
RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *config_ptr_);

launch_hw_ = declare_parameter<bool>("launch_hw", param_read_only());

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ ContinentalSRR520RosWrapper::ContinentalSRR520RosWrapper(const rclcpp::NodeOptio
(std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str());
}

RCLCPP_INFO_STREAM(get_logger(), "SensorConfig: " << *config_ptr_);
RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *config_ptr_);

launch_hw_ = declare_parameter<bool>("launch_hw", param_read_only());

Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/src/hesai/hesai_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options)
(std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str());
}

RCLCPP_INFO_STREAM(get_logger(), "SensorConfig: " << *sensor_cfg_ptr_);
RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *sensor_cfg_ptr_);

launch_hw_ = declare_parameter<bool>("launch_hw", param_read_only());

Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/src/hesai/hw_monitor_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ void HesaiHwMonitorWrapper::InitializeHesaiDiagnostics()
std::ostringstream os;
auto hardware_id = info_model_ + ": " + info_serial_;
diagnostics_updater_.setHardwareID(hardware_id);
RCLCPP_INFO_STREAM(logger_, "hardware_id: " + hardware_id);
RCLCPP_INFO_STREAM(logger_, "Hardware ID: " + hardware_id);

diagnostics_updater_.add("hesai_status", this, &HesaiHwMonitorWrapper::HesaiCheckStatus);
diagnostics_updater_.add("hesai_ptp", this, &HesaiHwMonitorWrapper::HesaiCheckPtp);
Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/src/robosense/robosense_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ RobosenseRosWrapper::RobosenseRosWrapper(const rclcpp::NodeOptions & options)
(std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str());
}

RCLCPP_INFO_STREAM(get_logger(), "SensorConfig: " << *sensor_cfg_ptr_);
RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *sensor_cfg_ptr_);

launch_hw_ = declare_parameter<bool>("launch_hw", param_read_only());

Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/src/velodyne/hw_monitor_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ void VelodyneHwMonitorWrapper::InitializeVelodyneDiagnostics()
std::ostringstream os;
auto hardware_id = info_model_ + ": " + info_serial_;
diagnostics_updater_.setHardwareID(hardware_id);
RCLCPP_INFO_STREAM(logger_, "hardware_id" << hardware_id);
RCLCPP_INFO_STREAM(logger_, "Hardware ID: " << hardware_id);

if (show_advanced_diagnostics_) {
diagnostics_updater_.add(
Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ VelodyneRosWrapper::VelodyneRosWrapper(const rclcpp::NodeOptions & options)
(std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str());
}

RCLCPP_INFO_STREAM(get_logger(), "SensorConfig: " << *sensor_cfg_ptr_);
RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *sensor_cfg_ptr_);

launch_hw_ = declare_parameter<bool>("launch_hw", param_read_only());

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ Status ContinentalRosDecoderTest::GetParameters(
return Status::INVALID_SENSOR_MODEL;
}

RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig: " << sensor_configuration);
RCLCPP_INFO_STREAM(this->get_logger(), "Sensor Configuration: " << sensor_configuration);
return Status::OK;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ Status ContinentalRosDecoderTest::GetParameters(
return Status::INVALID_SENSOR_MODEL;
}

RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig: " << sensor_configuration);
RCLCPP_INFO_STREAM(this->get_logger(), "Sensor Configuration: " << sensor_configuration);
return Status::OK;
}

Expand Down
2 changes: 1 addition & 1 deletion nebula_tests/hesai/hesai_ros_decoder_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -246,7 +246,7 @@ Status HesaiRosDecoderTest::GetParameters(
}
}

RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig: " << sensor_configuration);
RCLCPP_INFO_STREAM(this->get_logger(), "Sensor Configuration: " << sensor_configuration);
return Status::OK;
}

Expand Down
2 changes: 1 addition & 1 deletion nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -251,7 +251,7 @@ Status VelodyneRosDecoderTest::GetParameters(
}
}

RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig: " << sensor_configuration);
RCLCPP_INFO_STREAM(this->get_logger(), "Sensor Configuration: " << sensor_configuration);
return Status::OK;
}

Expand Down
2 changes: 1 addition & 1 deletion nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,7 @@ Status VelodyneRosDecoderTest::GetParameters(
}
}

RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig: " << sensor_configuration);
RCLCPP_INFO_STREAM(this->get_logger(), "Sensor Configuration: " << sensor_configuration);
return Status::OK;
}

Expand Down
2 changes: 1 addition & 1 deletion nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,7 @@ Status VelodyneRosDecoderTest::GetParameters(
}
}

RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig: " << sensor_configuration);
RCLCPP_INFO_STREAM(this->get_logger(), "Sensor Configuration: " << sensor_configuration);
return Status::OK;
}

Expand Down

0 comments on commit 7f8db71

Please sign in to comment.