diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/external_object_list_to_detection_list_component.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/external_object_list_to_detection_list_component.hpp index 180e55afa7..34f4fce202 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/external_object_list_to_detection_list_component.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/external_object_list_to_detection_list_component.hpp @@ -55,7 +55,7 @@ class ExternalObjectListToDetectionListNode : public carma_ros2_utils::CarmaLife auto publish_as_detection_list(const input_msg_type & msg) const -> void; - auto update_georeference(const std_msgs::msg::String & msg) noexcept -> void; + auto update_georeference(const std_msgs::msg::String & msg) -> void; private: rclcpp_lifecycle::LifecyclePublisher::SharedPtr publisher_{nullptr}; diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/external_object_list_to_sdsm_component.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/external_object_list_to_sdsm_component.hpp index e3ec19aaa3..8d947a5860 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/external_object_list_to_sdsm_component.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/external_object_list_to_sdsm_component.hpp @@ -53,9 +53,9 @@ class ExternalObjectListToSdsmNode : public carma_ros2_utils::CarmaLifecycleNode auto publish_as_sdsm(const external_objects_msg_type & msg) const -> void; - auto update_georeference(const georeference_msg_type & proj_string) noexcept -> void; + auto update_georeference(const georeference_msg_type & proj_string) -> void; - auto update_current_pose(const pose_msg_type & pose) noexcept -> void; + auto update_current_pose(const pose_msg_type & pose) -> void; private: rclcpp_lifecycle::LifecyclePublisher::SharedPtr sdsm_publisher_{nullptr}; diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/geodetic.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/geodetic.hpp index afd99fff28..618539a635 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/geodetic.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/geodetic.hpp @@ -65,8 +65,8 @@ struct UtmDisplacement * * @return Reference to the coordinate's updated position */ -inline constexpr auto operator+=( - UtmCoordinate & coordinate, const UtmDisplacement & displacement) noexcept -> UtmCoordinate & +inline constexpr auto operator+=(UtmCoordinate & coordinate, const UtmDisplacement & displacement) + -> UtmCoordinate & { coordinate.easting += displacement.easting; coordinate.northing += displacement.northing; @@ -83,8 +83,8 @@ inline constexpr auto operator+=( * * @return A new UtmCoordinate representing the new position */ -inline constexpr auto operator+( - UtmCoordinate coordinate, const UtmDisplacement & displacement) noexcept -> UtmCoordinate +inline constexpr auto operator+(UtmCoordinate coordinate, const UtmDisplacement & displacement) + -> UtmCoordinate { return coordinate += displacement; } @@ -97,8 +97,8 @@ inline constexpr auto operator+( * * @return A new UtmCoordinate representing the new position */ -inline constexpr auto operator+( - const UtmDisplacement & displacement, UtmCoordinate coordinate) noexcept -> UtmCoordinate +inline constexpr auto operator+(const UtmDisplacement & displacement, UtmCoordinate coordinate) + -> UtmCoordinate { return coordinate += displacement; } @@ -111,8 +111,8 @@ inline constexpr auto operator+( * * @return Reference to the coordinate's updated position */ -inline constexpr auto operator-=( - UtmCoordinate & coordinate, const UtmDisplacement & displacement) noexcept -> UtmCoordinate & +inline constexpr auto operator-=(UtmCoordinate & coordinate, const UtmDisplacement & displacement) + -> UtmCoordinate & { coordinate.easting += displacement.easting; coordinate.northing += displacement.northing; @@ -129,8 +129,8 @@ inline constexpr auto operator-=( * * @return A new UtmCoordinate representing the new position */ -inline constexpr auto operator-( - UtmCoordinate coordinate, const UtmDisplacement & displacement) noexcept -> UtmCoordinate +inline constexpr auto operator-(UtmCoordinate coordinate, const UtmDisplacement & displacement) + -> UtmCoordinate { return coordinate -= displacement; } @@ -143,8 +143,8 @@ inline constexpr auto operator-( * * @return A new UtmCoordinate representing the new position */ -inline constexpr auto operator-( - const UtmDisplacement & displacement, UtmCoordinate coordinate) noexcept -> UtmCoordinate +inline constexpr auto operator-(const UtmDisplacement & displacement, UtmCoordinate coordinate) + -> UtmCoordinate { return coordinate -= displacement; } diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/host_vehicle_filter_component.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/host_vehicle_filter_component.hpp index cc1613845e..328e16928e 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/host_vehicle_filter_component.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/host_vehicle_filter_component.hpp @@ -43,10 +43,10 @@ class HostVehicleFilterNode : public carma_ros2_utils::CarmaLifecycleNode auto handle_on_shutdown(const rclcpp_lifecycle::State & /* previous_state */) -> carma_ros2_utils::CallbackReturn override; - auto update_host_vehicle_pose(const geometry_msgs::msg::PoseStamped & msg) noexcept -> void; + auto update_host_vehicle_pose(const geometry_msgs::msg::PoseStamped & msg) -> void; - auto attempt_filter_and_republish( - carma_cooperative_perception_interfaces::msg::DetectionList msg) noexcept -> void; + auto attempt_filter_and_republish(carma_cooperative_perception_interfaces::msg::DetectionList msg) + -> void; private: rclcpp::Subscription::SharedPtr @@ -66,7 +66,7 @@ class HostVehicleFilterNode : public carma_ros2_utils::CarmaLifecycleNode }; auto euclidean_distance_squared( - const geometry_msgs::msg::Pose & a, const geometry_msgs::msg::Pose & b) noexcept -> double; + const geometry_msgs::msg::Pose & a, const geometry_msgs::msg::Pose & b) -> double; } // namespace carma_cooperative_perception diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/j2735_types.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/j2735_types.hpp index 52440c9e4d..95577ba550 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/j2735_types.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/j2735_types.hpp @@ -43,8 +43,7 @@ struct DDateTime std::optional second; std::optional time_zone_offset; - [[nodiscard]] static auto from_msg(const j2735_v2x_msgs::msg::DDateTime & msg) noexcept - -> DDateTime; + [[nodiscard]] static auto from_msg(const j2735_v2x_msgs::msg::DDateTime & msg) -> DDateTime; }; struct AccelerationSet4Way @@ -54,10 +53,10 @@ struct AccelerationSet4Way units::acceleration::two_centi_standard_gravities_t vert; units::angular_velocity::centi_degrees_per_second_t yaw_rate; - [[nodiscard]] static auto from_msg(const j2735_v2x_msgs::msg::AccelerationSet4Way & msg) noexcept + [[nodiscard]] static auto from_msg(const j2735_v2x_msgs::msg::AccelerationSet4Way & msg) -> AccelerationSet4Way; - [[nodiscard]] static auto from_msg(const carma_v2x_msgs::msg::AccelerationSet4Way & msg) noexcept + [[nodiscard]] static auto from_msg(const carma_v2x_msgs::msg::AccelerationSet4Way & msg) -> AccelerationSet4Way; }; @@ -67,31 +66,27 @@ struct Position3D units::angle::deci_micro_degrees_t longitude{0.0}; std::optional elevation; - [[nodiscard]] static auto from_msg(const j2735_v2x_msgs::msg::Position3D & msg) noexcept - -> Position3D; + [[nodiscard]] static auto from_msg(const j2735_v2x_msgs::msg::Position3D & msg) -> Position3D; - [[nodiscard]] static auto from_msg(const carma_v2x_msgs::msg::Position3D & msg) noexcept - -> Position3D; + [[nodiscard]] static auto from_msg(const carma_v2x_msgs::msg::Position3D & msg) -> Position3D; }; struct Heading { units::angle::eighth_deci_degrees_t heading; - [[nodiscard]] static auto from_msg(const j2735_v2x_msgs::msg::Heading & heading) noexcept - -> Heading; + [[nodiscard]] static auto from_msg(const j2735_v2x_msgs::msg::Heading & heading) -> Heading; - [[nodiscard]] static auto from_msg(const carma_v2x_msgs::msg::Heading & heading) noexcept - -> Heading; + [[nodiscard]] static auto from_msg(const carma_v2x_msgs::msg::Heading & heading) -> Heading; }; struct Speed { units::velocity::two_centi_meters_per_second_t speed; - [[nodiscard]] static auto from_msg(const j2735_v2x_msgs::msg::Speed & speed) noexcept -> Speed; + [[nodiscard]] static auto from_msg(const j2735_v2x_msgs::msg::Speed & speed) -> Speed; - [[nodiscard]] static auto from_msg(const carma_v2x_msgs::msg::Speed & speed) noexcept -> Speed; + [[nodiscard]] static auto from_msg(const carma_v2x_msgs::msg::Speed & speed) -> Speed; }; } // namespace carma_cooperative_perception diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/j3224_types.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/j3224_types.hpp index b0997395e2..4fd74f1ec2 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/j3224_types.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/j3224_types.hpp @@ -31,10 +31,10 @@ struct PositionOffsetXYZ units::length::decimeter_t offset_y{0.0}; std::optional offset_z; - [[nodiscard]] static auto from_msg(const j3224_v2x_msgs::msg::PositionOffsetXYZ & msg) noexcept + [[nodiscard]] static auto from_msg(const j3224_v2x_msgs::msg::PositionOffsetXYZ & msg) -> PositionOffsetXYZ; - [[nodiscard]] static auto from_msg(const carma_v2x_msgs::msg::PositionOffsetXYZ & msg) noexcept + [[nodiscard]] static auto from_msg(const carma_v2x_msgs::msg::PositionOffsetXYZ & msg) -> PositionOffsetXYZ; }; @@ -42,11 +42,11 @@ struct MeasurementTimeOffset { units::time::millisecond_t measurement_time_offset; - [[nodiscard]] static auto from_msg( - const j3224_v2x_msgs::msg::MeasurementTimeOffset & msg) noexcept -> MeasurementTimeOffset; + [[nodiscard]] static auto from_msg(const j3224_v2x_msgs::msg::MeasurementTimeOffset & msg) + -> MeasurementTimeOffset; - [[nodiscard]] static auto from_msg( - const carma_v2x_msgs::msg::MeasurementTimeOffset & msg) noexcept -> MeasurementTimeOffset; + [[nodiscard]] static auto from_msg(const carma_v2x_msgs::msg::MeasurementTimeOffset & msg) + -> MeasurementTimeOffset; }; } // namespace carma_cooperative_perception diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/month.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/month.hpp index 8ff2a27fab..c9eed3561f 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/month.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/month.hpp @@ -36,14 +36,14 @@ class Month * * @param[in] month_value Numerical value of the month; typically between [1, 12] */ - constexpr explicit Month(std::uint8_t month_value) noexcept : month_value_{month_value} {} + constexpr explicit Month(std::uint8_t month_value) : month_value_{month_value} {} /** * @brief Pre-increment operator overload * * @return Reference to Month instance being incremented */ - constexpr auto operator++() noexcept -> Month & + constexpr auto operator++() -> Month & { constexpr auto jan_value{1U}; constexpr auto dec_value{12U}; @@ -64,7 +64,7 @@ class Month * * @return Copy of Month instance before it was incremented */ - constexpr auto operator++(int /* dummy parameter */) noexcept -> Month + constexpr auto operator++(int /* dummy parameter */) -> Month { Month previous{*this}; ++(*this); @@ -77,7 +77,7 @@ class Month * * @return Reference to Month instance being decremented */ - constexpr auto operator--() noexcept -> Month & + constexpr auto operator--() -> Month & { constexpr auto dec_value{12U}; @@ -97,7 +97,7 @@ class Month * * @return Copy of Month instance before it was decremented */ - constexpr auto operator--(int /* dummy parameter */) noexcept -> Month + constexpr auto operator--(int /* dummy parameter */) -> Month { Month previous{*this}; --(*this); @@ -108,17 +108,14 @@ class Month /** * @brief Conversion function to convert Month instance to unsigned type */ - constexpr explicit operator unsigned() const noexcept - { - return static_cast(month_value_); - } + constexpr explicit operator unsigned() const { return static_cast(month_value_); } /** * @brief Checks if Month instance's value is within valid Gregorian calendar range * * @return true if Month instance's value is within [1, 12]; false otherwise */ - [[nodiscard]] constexpr auto ok() const noexcept -> bool + [[nodiscard]] constexpr auto ok() const -> bool { constexpr auto jan_value{1U}; constexpr auto dec_value{12U}; @@ -134,7 +131,7 @@ class Month * * @return true is Month instances are equal; false otherwise */ - friend constexpr auto operator==(const Month & x, const Month & y) noexcept -> bool + friend constexpr auto operator==(const Month & x, const Month & y) -> bool { return x.month_value_ == y.month_value_; } @@ -147,10 +144,7 @@ class Month * * @return true is Month instances are not equal; false otherwise */ - friend constexpr auto operator!=(const Month & x, const Month & y) noexcept -> bool - { - return !(x == y); - } + friend constexpr auto operator!=(const Month & x, const Month & y) -> bool { return !(x == y); } /** * @brief Check if one Month instance is less than another @@ -160,7 +154,7 @@ class Month * * @return true is x comes before y in the calendar; false otherwise */ - friend constexpr auto operator<(const Month & x, const Month & y) noexcept -> bool + friend constexpr auto operator<(const Month & x, const Month & y) -> bool { return x.month_value_ < y.month_value_; } @@ -173,7 +167,7 @@ class Month * * @return true is x comes before y in the calendar or if instances are equal; false otherwise */ - friend constexpr auto operator<=(const Month & x, const Month & y) noexcept -> bool + friend constexpr auto operator<=(const Month & x, const Month & y) -> bool { return x < y || x == y; } @@ -186,7 +180,7 @@ class Month * * @return true is x comes after y in the calendar; false otherwise */ - friend constexpr auto operator>(const Month & x, const Month & y) noexcept -> bool + friend constexpr auto operator>(const Month & x, const Month & y) -> bool { return x.month_value_ > y.month_value_; } @@ -199,7 +193,7 @@ class Month * * @return true is x comes after y in the calendar or if instances are equal; false otherwise */ - friend constexpr auto operator>=(const Month & x, const Month & y) noexcept -> bool + friend constexpr auto operator>=(const Month & x, const Month & y) -> bool { return x > y || x == y; } diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/msg_conversion.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/msg_conversion.hpp index 73b8674d1e..01167cebf6 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/msg_conversion.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/msg_conversion.hpp @@ -40,34 +40,34 @@ namespace carma_cooperative_perception { -auto to_time_msg(const DDateTime & d_date_time) noexcept -> builtin_interfaces::msg::Time; +auto to_time_msg(const DDateTime & d_date_time) -> builtin_interfaces::msg::Time; -auto calc_detection_time_stamp(DDateTime d_date_time, const MeasurementTimeOffset & offset) noexcept +auto calc_detection_time_stamp(DDateTime d_date_time, const MeasurementTimeOffset & offset) -> DDateTime; -auto to_ddate_time_msg(const builtin_interfaces::msg::Time & builtin_time) noexcept +auto to_ddate_time_msg(const builtin_interfaces::msg::Time & builtin_time) -> j2735_v2x_msgs::msg::DDateTime; auto calc_sdsm_time_offset( const builtin_interfaces::msg::Time & external_object_list_time, - const builtin_interfaces::msg::Time & external_object_time) noexcept + const builtin_interfaces::msg::Time & external_object_time) -> carma_v2x_msgs::msg::MeasurementTimeOffset; -auto to_position_msg(const UtmCoordinate & position_utm) noexcept -> geometry_msgs::msg::Point; +auto to_position_msg(const UtmCoordinate & position_utm) -> geometry_msgs::msg::Point; -auto heading_to_enu_yaw(const units::angle::degree_t & heading) noexcept -> units::angle::degree_t; +auto heading_to_enu_yaw(const units::angle::degree_t & heading) -> units::angle::degree_t; auto calc_relative_position( const geometry_msgs::msg::PoseStamped & current_pose, - const carma_v2x_msgs::msg::PositionOffsetXYZ & detected_object_data) noexcept + const carma_v2x_msgs::msg::PositionOffsetXYZ & detected_object_data) -> carma_v2x_msgs::msg::PositionOffsetXYZ; auto transform_pose_from_map_to_wgs84( const geometry_msgs::msg::PoseStamped & source_pose, - const std::shared_ptr & map_projection) noexcept + const std::shared_ptr & map_projection) -> carma_v2x_msgs::msg::Position3D; -auto to_detection_list_msg(const carma_v2x_msgs::msg::SensorDataSharingMessage & sdsm) noexcept +auto to_detection_list_msg(const carma_v2x_msgs::msg::SensorDataSharingMessage & sdsm) -> carma_cooperative_perception_interfaces::msg::DetectionList; struct MotionModelMapping @@ -86,36 +86,35 @@ struct MotionModelMapping auto to_detection_msg( const carma_perception_msgs::msg::ExternalObject & object, - const MotionModelMapping & motion_model_mapping) noexcept + const MotionModelMapping & motion_model_mapping) -> carma_cooperative_perception_interfaces::msg::Detection; auto to_detection_list_msg( const carma_perception_msgs::msg::ExternalObjectList & object_list, - const MotionModelMapping & motion_model_mapping) noexcept + const MotionModelMapping & motion_model_mapping) -> carma_cooperative_perception_interfaces::msg::DetectionList; -auto to_external_object_msg( - const carma_cooperative_perception_interfaces::msg::Track & track) noexcept +auto to_external_object_msg(const carma_cooperative_perception_interfaces::msg::Track & track) -> carma_perception_msgs::msg::ExternalObject; auto to_external_object_list_msg( - const carma_cooperative_perception_interfaces::msg::TrackList & track_list) noexcept + const carma_cooperative_perception_interfaces::msg::TrackList & track_list) -> carma_perception_msgs::msg::ExternalObjectList; auto to_sdsm_msg( const carma_perception_msgs::msg::ExternalObjectList & external_object_list, const geometry_msgs::msg::PoseStamped & current_pose, - const std::shared_ptr & map_projection) noexcept + const std::shared_ptr & map_projection) -> carma_v2x_msgs::msg::SensorDataSharingMessage; auto to_detected_object_data_msg( const carma_perception_msgs::msg::ExternalObject & external_object, - const std::shared_ptr & map_projection) noexcept + const std::shared_ptr & map_projection) -> carma_v2x_msgs::msg::DetectedObjectData; auto enu_orientation_to_true_heading( double yaw, const lanelet::BasicPoint3d & obj_pose, - const std::shared_ptr & map_projection) noexcept + const std::shared_ptr & map_projection) -> units::angle::degree_t; } // namespace carma_cooperative_perception diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/multiple_object_tracker_component.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/multiple_object_tracker_component.hpp index d2284f12db..92ad5bd4b1 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/multiple_object_tracker_component.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/multiple_object_tracker_component.hpp @@ -33,7 +33,8 @@ namespace carma_cooperative_perception using Detection = std::variant; -using Track = std::variant; +using Track = + std::variant; auto make_detection(const carma_cooperative_perception_interfaces::msg::Detection & msg) -> Detection; @@ -58,8 +59,8 @@ class MultipleObjectTrackerNode : public carma_ros2_utils::CarmaLifecycleNode auto handle_on_shutdown(const rclcpp_lifecycle::State & /* previous_state */) -> carma_ros2_utils::CallbackReturn override; - auto store_new_detections( - const carma_cooperative_perception_interfaces::msg::DetectionList & msg) noexcept -> void; + auto store_new_detections(const carma_cooperative_perception_interfaces::msg::DetectionList & msg) + -> void; auto execute_pipeline() -> void; @@ -75,7 +76,8 @@ class MultipleObjectTrackerNode : public carma_ros2_utils::CarmaLifecycleNode std::vector detections_; std::unordered_map uuid_index_map_; multiple_object_tracking::FixedThresholdTrackManager track_manager_{ - multiple_object_tracking::PromotionThreshold{3U}, multiple_object_tracking::RemovalThreshold{0U}}; + multiple_object_tracking::PromotionThreshold{3U}, + multiple_object_tracking::RemovalThreshold{0U}}; units::time::nanosecond_t execution_period_{1 / units::frequency::hertz_t{2.0}}; OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_{nullptr}; }; diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/sdsm_to_detection_list_component.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/sdsm_to_detection_list_component.hpp index a805b079ba..ee1bc64ef4 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/sdsm_to_detection_list_component.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/sdsm_to_detection_list_component.hpp @@ -39,7 +39,7 @@ class SdsmToDetectionListNode : public carma_ros2_utils::CarmaLifecycleNode { } - auto sdsm_msg_callback(const input_msg_type & msg) const noexcept -> void + auto sdsm_msg_callback(const input_msg_type & msg) const -> void { publisher_->publish(to_detection_list_msg(msg)); } diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/track_list_to_external_object_list_component.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/track_list_to_external_object_list_component.hpp index b1cefb1fe2..7a54fc70c6 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/track_list_to_external_object_list_component.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/track_list_to_external_object_list_component.hpp @@ -44,7 +44,7 @@ class TrackListToExternalObjectListNode : public carma_ros2_utils::CarmaLifecycl -> carma_ros2_utils::CallbackReturn override; auto publish_as_external_object_list( - const carma_cooperative_perception_interfaces::msg::TrackList & msg) const noexcept -> void; + const carma_cooperative_perception_interfaces::msg::TrackList & msg) const -> void; private: rclcpp_lifecycle::LifecyclePublisher::SharedPtr diff --git a/carma_cooperative_perception/include/carma_cooperative_perception/units_extensions.hpp b/carma_cooperative_perception/include/carma_cooperative_perception/units_extensions.hpp index c212ed1f6b..0de93b6222 100644 --- a/carma_cooperative_perception/include/carma_cooperative_perception/units_extensions.hpp +++ b/carma_cooperative_perception/include/carma_cooperative_perception/units_extensions.hpp @@ -22,7 +22,7 @@ namespace carma_cooperative_perception { template -constexpr auto remove_units(const T & value) noexcept +constexpr auto remove_units(const T & value) { return units::unit_cast(value); } diff --git a/carma_cooperative_perception/src/external_object_list_to_detection_list_component.cpp b/carma_cooperative_perception/src/external_object_list_to_detection_list_component.cpp index e3eebb3fb0..5014d98545 100644 --- a/carma_cooperative_perception/src/external_object_list_to_detection_list_component.cpp +++ b/carma_cooperative_perception/src/external_object_list_to_detection_list_component.cpp @@ -192,8 +192,8 @@ auto ExternalObjectListToDetectionListNode::publish_as_detection_list( } } -auto ExternalObjectListToDetectionListNode::update_georeference( - const std_msgs::msg::String & msg) noexcept -> void +auto ExternalObjectListToDetectionListNode::update_georeference(const std_msgs::msg::String & msg) + -> void { map_georeference_ = msg.data; } diff --git a/carma_cooperative_perception/src/external_object_list_to_detection_list_node.cpp b/carma_cooperative_perception/src/external_object_list_to_detection_list_node.cpp index 4fc064eaec..71efa46df3 100644 --- a/carma_cooperative_perception/src/external_object_list_to_detection_list_node.cpp +++ b/carma_cooperative_perception/src/external_object_list_to_detection_list_node.cpp @@ -18,7 +18,7 @@ #include -auto main(int argc, char * argv[]) noexcept -> int +auto main(int argc, char * argv[]) -> int { rclcpp::init(argc, argv); diff --git a/carma_cooperative_perception/src/external_object_list_to_sdsm_component.cpp b/carma_cooperative_perception/src/external_object_list_to_sdsm_component.cpp index c12c9004f5..a3e9b8779d 100644 --- a/carma_cooperative_perception/src/external_object_list_to_sdsm_component.cpp +++ b/carma_cooperative_perception/src/external_object_list_to_sdsm_component.cpp @@ -17,8 +17,8 @@ #include #include -#include "carma_cooperative_perception/msg_conversion.hpp" #include +#include "carma_cooperative_perception/msg_conversion.hpp" namespace carma_cooperative_perception { @@ -128,15 +128,13 @@ auto ExternalObjectListToSdsmNode::publish_as_sdsm(const external_objects_msg_ty } } -auto ExternalObjectListToSdsmNode::update_georeference(const georeference_msg_type & msg) noexcept - -> void +auto ExternalObjectListToSdsmNode::update_georeference(const georeference_msg_type & msg) -> void { map_georeference_ = msg.data; map_projector_ = std::make_shared(msg.data.c_str()); } -auto ExternalObjectListToSdsmNode::update_current_pose(const pose_msg_type & msg) noexcept - -> void +auto ExternalObjectListToSdsmNode::update_current_pose(const pose_msg_type & msg) -> void { current_pose_ = msg; } diff --git a/carma_cooperative_perception/src/external_object_list_to_sdsm_node.cpp b/carma_cooperative_perception/src/external_object_list_to_sdsm_node.cpp index 010e145cbc..e6b1cdae97 100644 --- a/carma_cooperative_perception/src/external_object_list_to_sdsm_node.cpp +++ b/carma_cooperative_perception/src/external_object_list_to_sdsm_node.cpp @@ -18,7 +18,7 @@ #include -auto main(int argc, char * argv[]) noexcept -> int +auto main(int argc, char * argv[]) -> int { rclcpp::init(argc, argv); diff --git a/carma_cooperative_perception/src/host_vehicle_filter_component.cpp b/carma_cooperative_perception/src/host_vehicle_filter_component.cpp index 7adab412cf..7147a0dc01 100644 --- a/carma_cooperative_perception/src/host_vehicle_filter_component.cpp +++ b/carma_cooperative_perception/src/host_vehicle_filter_component.cpp @@ -153,14 +153,14 @@ auto HostVehicleFilterNode::handle_on_shutdown(const rclcpp_lifecycle::State & / return carma_ros2_utils::CallbackReturn::SUCCESS; } -auto HostVehicleFilterNode::update_host_vehicle_pose( - const geometry_msgs::msg::PoseStamped & msg) noexcept -> void +auto HostVehicleFilterNode::update_host_vehicle_pose(const geometry_msgs::msg::PoseStamped & msg) + -> void { host_vehicle_pose_ = msg; } auto HostVehicleFilterNode::attempt_filter_and_republish( - carma_cooperative_perception_interfaces::msg::DetectionList msg) noexcept -> void + carma_cooperative_perception_interfaces::msg::DetectionList msg) -> void { if (!host_vehicle_pose_.has_value()) { RCLCPP_WARN(get_logger(), "Could not filter detection list: host vehicle pose unknown"); @@ -181,7 +181,7 @@ auto HostVehicleFilterNode::attempt_filter_and_republish( } auto euclidean_distance_squared( - const geometry_msgs::msg::Pose & a, const geometry_msgs::msg::Pose & b) noexcept -> double + const geometry_msgs::msg::Pose & a, const geometry_msgs::msg::Pose & b) -> double { return std::pow(a.position.x - b.position.x, 2) + std::pow(a.position.y - b.position.y, 2) + std::pow(a.position.z - b.position.z, 2) + std::pow(a.orientation.x - b.orientation.x, 2) + diff --git a/carma_cooperative_perception/src/host_vehicle_filter_node.cpp b/carma_cooperative_perception/src/host_vehicle_filter_node.cpp index 529c485f01..c6e65810cc 100644 --- a/carma_cooperative_perception/src/host_vehicle_filter_node.cpp +++ b/carma_cooperative_perception/src/host_vehicle_filter_node.cpp @@ -18,7 +18,7 @@ #include -auto main(int argc, char * argv[]) noexcept -> int +auto main(int argc, char * argv[]) -> int { rclcpp::init(argc, argv); diff --git a/carma_cooperative_perception/src/j2735_types.cpp b/carma_cooperative_perception/src/j2735_types.cpp index b605e33088..0132aedb82 100644 --- a/carma_cooperative_perception/src/j2735_types.cpp +++ b/carma_cooperative_perception/src/j2735_types.cpp @@ -16,7 +16,7 @@ namespace carma_cooperative_perception { -auto DDateTime::from_msg(const j2735_v2x_msgs::msg::DDateTime & msg) noexcept -> DDateTime +auto DDateTime::from_msg(const j2735_v2x_msgs::msg::DDateTime & msg) -> DDateTime { DDateTime d_date_time; @@ -52,7 +52,7 @@ auto DDateTime::from_msg(const j2735_v2x_msgs::msg::DDateTime & msg) noexcept -> return d_date_time; } -auto AccelerationSet4Way::from_msg(const j2735_v2x_msgs::msg::AccelerationSet4Way & msg) noexcept +auto AccelerationSet4Way::from_msg(const j2735_v2x_msgs::msg::AccelerationSet4Way & msg) -> AccelerationSet4Way { return { @@ -62,7 +62,7 @@ auto AccelerationSet4Way::from_msg(const j2735_v2x_msgs::msg::AccelerationSet4Wa units::angular_velocity::centi_degrees_per_second_t{static_cast(msg.yaw_rate)}}; } -auto AccelerationSet4Way::from_msg(const carma_v2x_msgs::msg::AccelerationSet4Way & msg) noexcept +auto AccelerationSet4Way::from_msg(const carma_v2x_msgs::msg::AccelerationSet4Way & msg) -> AccelerationSet4Way { return { @@ -72,7 +72,7 @@ auto AccelerationSet4Way::from_msg(const carma_v2x_msgs::msg::AccelerationSet4Wa units::angular_velocity::degrees_per_second_t{static_cast(msg.yaw_rate)}}; } -auto Position3D::from_msg(const j2735_v2x_msgs::msg::Position3D & msg) noexcept -> Position3D +auto Position3D::from_msg(const j2735_v2x_msgs::msg::Position3D & msg) -> Position3D { Position3D position{ units::angle::deci_micro_degrees_t{static_cast(msg.latitude)}, @@ -85,7 +85,7 @@ auto Position3D::from_msg(const j2735_v2x_msgs::msg::Position3D & msg) noexcept return position; } -auto Position3D::from_msg(const carma_v2x_msgs::msg::Position3D & msg) noexcept -> Position3D +auto Position3D::from_msg(const carma_v2x_msgs::msg::Position3D & msg) -> Position3D { Position3D position{ units::angle::degree_t{static_cast(msg.latitude)}, @@ -98,22 +98,22 @@ auto Position3D::from_msg(const carma_v2x_msgs::msg::Position3D & msg) noexcept return position; } -auto Heading::from_msg(const j2735_v2x_msgs::msg::Heading & heading) noexcept -> Heading +auto Heading::from_msg(const j2735_v2x_msgs::msg::Heading & heading) -> Heading { return {units::angle::eighth_deci_degrees_t{static_cast(heading.heading)}}; } -auto Heading::from_msg(const carma_v2x_msgs::msg::Heading & heading) noexcept -> Heading +auto Heading::from_msg(const carma_v2x_msgs::msg::Heading & heading) -> Heading { return {units::angle::degree_t{static_cast(heading.heading)}}; } -auto Speed::from_msg(const j2735_v2x_msgs::msg::Speed & speed) noexcept -> Speed +auto Speed::from_msg(const j2735_v2x_msgs::msg::Speed & speed) -> Speed { return {units::velocity::two_centi_meters_per_second_t{static_cast(speed.speed)}}; } -auto Speed::from_msg(const carma_v2x_msgs::msg::Speed & speed) noexcept -> Speed +auto Speed::from_msg(const carma_v2x_msgs::msg::Speed & speed) -> Speed { return {units::velocity::meters_per_second_t{static_cast(speed.speed)}}; } diff --git a/carma_cooperative_perception/src/j3224_types.cpp b/carma_cooperative_perception/src/j3224_types.cpp index e95a43ae81..fbad26bc47 100644 --- a/carma_cooperative_perception/src/j3224_types.cpp +++ b/carma_cooperative_perception/src/j3224_types.cpp @@ -16,7 +16,7 @@ namespace carma_cooperative_perception { -auto PositionOffsetXYZ::from_msg(const j3224_v2x_msgs::msg::PositionOffsetXYZ & msg) noexcept +auto PositionOffsetXYZ::from_msg(const j3224_v2x_msgs::msg::PositionOffsetXYZ & msg) -> PositionOffsetXYZ { PositionOffsetXYZ offset{ @@ -30,7 +30,7 @@ auto PositionOffsetXYZ::from_msg(const j3224_v2x_msgs::msg::PositionOffsetXYZ & return offset; } -auto PositionOffsetXYZ::from_msg(const carma_v2x_msgs::msg::PositionOffsetXYZ & msg) noexcept +auto PositionOffsetXYZ::from_msg(const carma_v2x_msgs::msg::PositionOffsetXYZ & msg) -> PositionOffsetXYZ { PositionOffsetXYZ offset{ @@ -44,14 +44,14 @@ auto PositionOffsetXYZ::from_msg(const carma_v2x_msgs::msg::PositionOffsetXYZ & return offset; } -auto MeasurementTimeOffset::from_msg( - const j3224_v2x_msgs::msg::MeasurementTimeOffset & msg) noexcept -> MeasurementTimeOffset +auto MeasurementTimeOffset::from_msg(const j3224_v2x_msgs::msg::MeasurementTimeOffset & msg) + -> MeasurementTimeOffset { return {units::time::millisecond_t{static_cast(msg.measurement_time_offset)}}; } -auto MeasurementTimeOffset::from_msg( - const carma_v2x_msgs::msg::MeasurementTimeOffset & msg) noexcept -> MeasurementTimeOffset +auto MeasurementTimeOffset::from_msg(const carma_v2x_msgs::msg::MeasurementTimeOffset & msg) + -> MeasurementTimeOffset { return {units::time::second_t{static_cast(msg.measurement_time_offset)}}; } diff --git a/carma_cooperative_perception/src/msg_conversion.cpp b/carma_cooperative_perception/src/msg_conversion.cpp index 71f4851cc5..648a2eb81a 100644 --- a/carma_cooperative_perception/src/msg_conversion.cpp +++ b/carma_cooperative_perception/src/msg_conversion.cpp @@ -48,7 +48,7 @@ namespace carma_cooperative_perception { -auto to_time_msg(const DDateTime & d_date_time) noexcept -> builtin_interfaces::msg::Time +auto to_time_msg(const DDateTime & d_date_time) -> builtin_interfaces::msg::Time { double seconds; const auto fractional_secs{ @@ -61,7 +61,7 @@ auto to_time_msg(const DDateTime & d_date_time) noexcept -> builtin_interfaces:: return msg; } -auto calc_detection_time_stamp(DDateTime sdsm_time, const MeasurementTimeOffset & offset) noexcept +auto calc_detection_time_stamp(DDateTime sdsm_time, const MeasurementTimeOffset & offset) -> DDateTime { sdsm_time.second.value() += offset.measurement_time_offset; @@ -69,7 +69,7 @@ auto calc_detection_time_stamp(DDateTime sdsm_time, const MeasurementTimeOffset return sdsm_time; } -auto to_ddate_time_msg(const builtin_interfaces::msg::Time & builtin_time) noexcept +auto to_ddate_time_msg(const builtin_interfaces::msg::Time & builtin_time) -> j2735_v2x_msgs::msg::DDateTime { j2735_v2x_msgs::msg::DDateTime ddate_time_output; @@ -106,7 +106,7 @@ auto to_ddate_time_msg(const builtin_interfaces::msg::Time & builtin_time) noexc auto calc_sdsm_time_offset( const builtin_interfaces::msg::Time & external_object_list_stamp, - const builtin_interfaces::msg::Time & external_object_stamp) noexcept + const builtin_interfaces::msg::Time & external_object_stamp) -> carma_v2x_msgs::msg::MeasurementTimeOffset { carma_v2x_msgs::msg::MeasurementTimeOffset time_offset; @@ -127,7 +127,7 @@ auto calc_sdsm_time_offset( return time_offset; } -auto to_position_msg(const UtmCoordinate & position_utm) noexcept -> geometry_msgs::msg::Point +auto to_position_msg(const UtmCoordinate & position_utm) -> geometry_msgs::msg::Point { geometry_msgs::msg::Point msg; @@ -138,14 +138,14 @@ auto to_position_msg(const UtmCoordinate & position_utm) noexcept -> geometry_ms return msg; } -auto heading_to_enu_yaw(const units::angle::degree_t & heading) noexcept -> units::angle::degree_t +auto heading_to_enu_yaw(const units::angle::degree_t & heading) -> units::angle::degree_t { return units::angle::degree_t{std::fmod(-(remove_units(heading) - 90.0) + 360.0, 360.0)}; } auto enu_orientation_to_true_heading( double yaw, const lanelet::BasicPoint3d & obj_pose, - const std::shared_ptr & map_projection) noexcept + const std::shared_ptr & map_projection) -> units::angle::degree_t { // Get object geodetic position @@ -172,7 +172,7 @@ auto enu_orientation_to_true_heading( // in map frame and external object pose auto calc_relative_position( const geometry_msgs::msg::PoseStamped & source_pose, - const carma_v2x_msgs::msg::PositionOffsetXYZ & position_offset) noexcept + const carma_v2x_msgs::msg::PositionOffsetXYZ & position_offset) -> carma_v2x_msgs::msg::PositionOffsetXYZ { carma_v2x_msgs::msg::PositionOffsetXYZ adjusted_offset; @@ -190,7 +190,7 @@ auto calc_relative_position( auto transform_pose_from_map_to_wgs84( const geometry_msgs::msg::PoseStamped & source_pose, - const std::shared_ptr & map_projection) noexcept + const std::shared_ptr & map_projection) -> carma_v2x_msgs::msg::Position3D { carma_v2x_msgs::msg::Position3D ref_pos; @@ -207,7 +207,7 @@ auto transform_pose_from_map_to_wgs84( return ref_pos; } -auto to_detection_list_msg(const carma_v2x_msgs::msg::SensorDataSharingMessage & sdsm) noexcept +auto to_detection_list_msg(const carma_v2x_msgs::msg::SensorDataSharingMessage & sdsm) -> carma_cooperative_perception_interfaces::msg::DetectionList { carma_cooperative_perception_interfaces::msg::DetectionList detection_list; @@ -297,7 +297,7 @@ auto to_detection_list_msg(const carma_v2x_msgs::msg::SensorDataSharingMessage & auto to_detection_msg( const carma_perception_msgs::msg::ExternalObject & object, - const MotionModelMapping & motion_model_mapping) noexcept + const MotionModelMapping & motion_model_mapping) -> carma_cooperative_perception_interfaces::msg::Detection { carma_cooperative_perception_interfaces::msg::Detection detection; @@ -353,7 +353,7 @@ auto to_detection_msg( auto to_detection_list_msg( const carma_perception_msgs::msg::ExternalObjectList & object_list, - const MotionModelMapping & motion_model_mapping) noexcept + const MotionModelMapping & motion_model_mapping) -> carma_cooperative_perception_interfaces::msg::DetectionList { carma_cooperative_perception_interfaces::msg::DetectionList detection_list; @@ -368,8 +368,7 @@ auto to_detection_list_msg( return detection_list; } -auto to_external_object_msg( - const carma_cooperative_perception_interfaces::msg::Track & track) noexcept +auto to_external_object_msg(const carma_cooperative_perception_interfaces::msg::Track & track) -> carma_perception_msgs::msg::ExternalObject { carma_perception_msgs::msg::ExternalObject external_object; @@ -430,7 +429,7 @@ auto to_external_object_msg( } auto to_external_object_list_msg( - const carma_cooperative_perception_interfaces::msg::TrackList & track_list) noexcept + const carma_cooperative_perception_interfaces::msg::TrackList & track_list) -> carma_perception_msgs::msg::ExternalObjectList { carma_perception_msgs::msg::ExternalObjectList external_object_list; @@ -445,7 +444,7 @@ auto to_external_object_list_msg( auto to_sdsm_msg( const carma_perception_msgs::msg::ExternalObjectList & external_object_list, const geometry_msgs::msg::PoseStamped & current_pose, - const std::shared_ptr & map_projection) noexcept + const std::shared_ptr & map_projection) -> carma_v2x_msgs::msg::SensorDataSharingMessage { carma_v2x_msgs::msg::SensorDataSharingMessage sdsm; @@ -476,7 +475,7 @@ auto to_sdsm_msg( auto to_detected_object_data_msg( const carma_perception_msgs::msg::ExternalObject & external_object, - const std::shared_ptr & map_projection) noexcept + const std::shared_ptr & map_projection) -> carma_v2x_msgs::msg::DetectedObjectData { carma_v2x_msgs::msg::DetectedObjectData detected_object_data; diff --git a/carma_cooperative_perception/src/multiple_object_tracker_component.cpp b/carma_cooperative_perception/src/multiple_object_tracker_component.cpp index b3bff5b2d7..da173b9deb 100644 --- a/carma_cooperative_perception/src/multiple_object_tracker_component.cpp +++ b/carma_cooperative_perception/src/multiple_object_tracker_component.cpp @@ -72,8 +72,8 @@ auto semantic_class_to_numeric_value(mot::SemanticClass semantic_class) return 0; } -auto make_ctrv_detection( - const carma_cooperative_perception_interfaces::msg::Detection & msg) noexcept -> Detection +auto make_ctrv_detection(const carma_cooperative_perception_interfaces::msg::Detection & msg) + -> Detection { const auto timestamp{ units::time::second_t{static_cast(msg.header.stamp.sec)} + @@ -110,8 +110,8 @@ auto make_ctrv_detection( timestamp, state, covariance, mot::Uuid{msg.id}, make_semantic_class(msg.semantic_class)}; } -auto make_ctra_detection( - const carma_cooperative_perception_interfaces::msg::Detection & msg) noexcept -> Detection +auto make_ctra_detection(const carma_cooperative_perception_interfaces::msg::Detection & msg) + -> Detection { const auto timestamp{ units::time::second_t{static_cast(msg.header.stamp.sec)} + @@ -167,7 +167,7 @@ auto make_detection(const carma_cooperative_perception_interfaces::msg::Detectio throw std::runtime_error("unkown motion model type '" + std::to_string(msg.motion_model) + "'"); } -static auto to_ros_msg(const mot::CtraTrack & track) noexcept +static auto to_ros_msg(const mot::CtraTrack & track) { carma_cooperative_perception_interfaces::msg::Track msg; @@ -198,7 +198,7 @@ static auto to_ros_msg(const mot::CtraTrack & track) noexcept return msg; } -static auto to_ros_msg(const mot::CtrvTrack & track) noexcept +static auto to_ros_msg(const mot::CtrvTrack & track) { carma_cooperative_perception_interfaces::msg::Track msg; @@ -405,7 +405,7 @@ auto MultipleObjectTrackerNode::handle_on_shutdown( } auto MultipleObjectTrackerNode::store_new_detections( - const carma_cooperative_perception_interfaces::msg::DetectionList & msg) noexcept -> void + const carma_cooperative_perception_interfaces::msg::DetectionList & msg) -> void { if (std::size(msg.detections) == 0) { RCLCPP_WARN(this->get_logger(), "Not storing detections: incoming detection list is empty"); @@ -435,14 +435,14 @@ auto MultipleObjectTrackerNode::store_new_detections( } static auto temporally_align_detections( - std::vector & detections, units::time::second_t end_time) noexcept -> void + std::vector & detections, units::time::second_t end_time) -> void { for (auto & detection : detections) { mot::propagate_to_time(detection, end_time, mot::default_unscented_transform); } } -static auto predict_track_states(std::vector tracks, units::time::second_t end_time) noexcept +static auto predict_track_states(std::vector tracks, units::time::second_t end_time) { for (auto & track : tracks) { mot::propagate_to_time(track, end_time, mot::default_unscented_transform); diff --git a/carma_cooperative_perception/src/multiple_object_tracker_node.cpp b/carma_cooperative_perception/src/multiple_object_tracker_node.cpp index f4281e527a..d0c7c65070 100644 --- a/carma_cooperative_perception/src/multiple_object_tracker_node.cpp +++ b/carma_cooperative_perception/src/multiple_object_tracker_node.cpp @@ -18,7 +18,7 @@ #include -auto main(int argc, char * argv[]) noexcept -> int +auto main(int argc, char * argv[]) -> int { rclcpp::init(argc, argv); diff --git a/carma_cooperative_perception/src/track_list_to_external_object_list_component.cpp b/carma_cooperative_perception/src/track_list_to_external_object_list_component.cpp index 7021c8875b..0003432088 100644 --- a/carma_cooperative_perception/src/track_list_to_external_object_list_component.cpp +++ b/carma_cooperative_perception/src/track_list_to_external_object_list_component.cpp @@ -76,7 +76,7 @@ auto TrackListToExternalObjectListNode::handle_on_shutdown( } auto TrackListToExternalObjectListNode::publish_as_external_object_list( - const carma_cooperative_perception_interfaces::msg::TrackList & msg) const noexcept -> void + const carma_cooperative_perception_interfaces::msg::TrackList & msg) const -> void { auto external_object_list{to_external_object_list_msg(msg)}; external_object_list.header.stamp = now(); diff --git a/carma_cooperative_perception/src/track_list_to_external_object_list_node.cpp b/carma_cooperative_perception/src/track_list_to_external_object_list_node.cpp index b6a1633999..efffb84f02 100644 --- a/carma_cooperative_perception/src/track_list_to_external_object_list_node.cpp +++ b/carma_cooperative_perception/src/track_list_to_external_object_list_node.cpp @@ -18,7 +18,7 @@ #include -auto main(int argc, char * argv[]) noexcept -> int +auto main(int argc, char * argv[]) -> int { rclcpp::init(argc, argv);