Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
sdsm_to_detection_list_component.hpp
Go to the documentation of this file.
1// Copyright 2023 Leidos
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef CARMA_COOPERATIVE_PERCEPTION__SDSM_TO_DETECTION_LIST_COMPONENT_HPP_
16#define CARMA_COOPERATIVE_PERCEPTION__SDSM_TO_DETECTION_LIST_COMPONENT_HPP_
17
18#include <string>
19
20#include <carma_cooperative_perception_interfaces/msg/detection_list.hpp>
21#include <carma_ros2_utils/carma_lifecycle_node.hpp>
22#include <carma_v2x_msgs/msg/sensor_data_sharing_message.hpp>
23#include <rclcpp/rclcpp.hpp>
24#include <rosgraph_msgs/msg/clock.hpp>
25#include <std_msgs/msg/string.hpp>
26
28
30{
31
32class SdsmToDetectionListNode : public carma_ros2_utils::CarmaLifecycleNode
33{
34 using input_msg_type = carma_v2x_msgs::msg::SensorDataSharingMessage;
35 using input_msg_shared_pointer = typename input_msg_type::SharedPtr;
36 using output_msg_type = carma_cooperative_perception_interfaces::msg::DetectionList;
37
38public:
39 auto handle_on_configure(const rclcpp_lifecycle::State & /* previous_state */)
40 -> carma_ros2_utils::CallbackReturn override
41 {
42 // Declare parameters
43 declare_parameter("overwrite_covariance", config_.overwrite_covariance);
44 declare_parameter("pose_covariance_x", config_.pose_covariance_x);
45 declare_parameter("pose_covariance_y", config_.pose_covariance_y);
46 declare_parameter("pose_covariance_z", config_.pose_covariance_z);
47 declare_parameter("pose_covariance_yaw", config_.pose_covariance_yaw);
48 declare_parameter("twist_covariance_x", config_.twist_covariance_x);
49 declare_parameter("twist_covariance_z", config_.twist_covariance_z);
50 declare_parameter("twist_covariance_yaw", config_.twist_covariance_yaw);
51 declare_parameter("adjust_pose", config_.adjust_pose);
52 declare_parameter("x_offset", config_.x_offset);
53 declare_parameter("y_offset", config_.y_offset);
54 declare_parameter("yaw_offset", config_.yaw_offset);
55
56 // Get parameters
57 config_.overwrite_covariance = get_parameter("overwrite_covariance").as_bool();
58 config_.pose_covariance_x = get_parameter("pose_covariance_x").as_double();
59 config_.pose_covariance_y = get_parameter("pose_covariance_y").as_double();
60 config_.pose_covariance_z = get_parameter("pose_covariance_z").as_double();
61 config_.pose_covariance_yaw = get_parameter("pose_covariance_yaw").as_double();
62 config_.twist_covariance_x = get_parameter("twist_covariance_x").as_double();
63 config_.twist_covariance_z = get_parameter("twist_covariance_z").as_double();
64 config_.adjust_pose = get_parameter("adjust_pose").as_bool();
65 config_.x_offset = get_parameter("x_offset").as_double();
66 config_.y_offset = get_parameter("y_offset").as_double();
67 config_.yaw_offset = get_parameter("yaw_offset").as_double();
68
69 // Set up parameter validation callback
70 on_set_parameters_callback_ = add_on_set_parameters_callback(
71 [this](const std::vector<rclcpp::Parameter> & parameters) {
72 return update_parameters(parameters);
73 });
74
75 // Use the stream operator for debug output
76 RCLCPP_INFO_STREAM(get_logger(), "SdsmToDetectionListNode Configuration: " << config_);
77
78 return carma_ros2_utils::CallbackReturn::SUCCESS;
79 }
80
81 explicit SdsmToDetectionListNode(const rclcpp::NodeOptions & options)
82 : CarmaLifecycleNode{options},
83 publisher_{create_publisher<output_msg_type>("output/detections", 1)},
84 subscription_{create_subscription<input_msg_type>(
85 "input/sdsm", 100, [this](input_msg_shared_pointer msg_ptr) { sdsm_msg_callback(*msg_ptr); })},
86 georeference_subscription_{create_subscription<std_msgs::msg::String>(
87 "input/georeference", 1,
88 [this](std_msgs::msg::String::SharedPtr msg_ptr) { georeference_ = msg_ptr->data; })},
89 cdasim_clock_sub_{create_subscription<rosgraph_msgs::msg::Clock>(
90 "input/cdasim_clock", 1,
91 [this](rosgraph_msgs::msg::Clock::ConstSharedPtr msg_ptr) { cdasim_time_ = msg_ptr->clock; })}
92 {
93 // Initialize the valid parameter names to check when setting the at runtime
94 valid_parameter_names_ = {
95 "overwrite_covariance",
96 "pose_covariance_x",
97 "pose_covariance_y",
98 "pose_covariance_z",
99 "pose_covariance_yaw",
100 "twist_covariance_x",
101 "twist_covariance_z",
102 "twist_covariance_yaw",
103 "adjust_pose",
104 "x_offset",
105 "y_offset",
106 "yaw_offset"
107 };
108 }
109
110 auto sdsm_msg_callback(const input_msg_type & msg) const -> void
111 {
112 try {
113 std::optional<SdsmToDetectionListConfig> conversion_adjustment = std::nullopt;
114 if (config_.overwrite_covariance || config_.adjust_pose) {
115 conversion_adjustment = config_;
116 }
117 auto detection_list_msg{
118 to_detection_list_msg(msg, georeference_, cdasim_time_ != std::nullopt,
119 conversion_adjustment)
120 };
121
122 if (cdasim_time_) {
123 // When in simulation, ROS time is CARLA time, but SDSMs use CDASim time
124 const auto time_delta{now() - cdasim_time_.value()};
125
126 for (auto & detection : detection_list_msg.detections) {
127 detection.header.stamp = rclcpp::Time(detection.header.stamp) + time_delta;
128 }
129 }
130 RCLCPP_DEBUG_STREAM(
131 get_logger(), "SDSM to detection list conversion: "
132 << detection_list_msg.detections.size() << " detections");
133 publisher_->publish(detection_list_msg);
134 } catch (const std::runtime_error & e) {
135 RCLCPP_ERROR_STREAM(get_logger(), "Failed to convert SDSM to detection list: " << e.what());
136 }
137 }
138
139private:
140 rclcpp::Publisher<output_msg_type>::SharedPtr publisher_;
141 rclcpp::Subscription<input_msg_type>::SharedPtr subscription_;
142 rclcpp::Subscription<std_msgs::msg::String>::SharedPtr georeference_subscription_;
143
144 rclcpp::Subscription<rosgraph_msgs::msg::Clock>::SharedPtr cdasim_clock_sub_;
145 std::optional<rclcpp::Time> cdasim_time_{std::nullopt};
146
147 std::string georeference_{""};
148
149 // Configuration object
151
152 OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_{nullptr};
153
154 // Parameter validation function
155 rcl_interfaces::msg::SetParametersResult update_parameters(
156 const std::vector<rclcpp::Parameter> & parameters)
157 {
158 rcl_interfaces::msg::SetParametersResult result;
159 result.successful = true;
160 result.reason = "success";
161
162 for (const auto & parameter : parameters) {
163 // Check if parameter name is valid
164 if (valid_parameter_names_.find(parameter.get_name()) == valid_parameter_names_.end()) {
165 result.successful = false;
166 result.reason = "Unexpected parameter name '" + parameter.get_name() + "'";
167 RCLCPP_ERROR_STREAM(get_logger(), "Cannot change parameter: " << result.reason);
168 break;
169 }
170
171 // Validate covariance values (must be non-negative)
172 if (parameter.get_name() != "adjust_pose" &&
173 parameter.get_name() != "overwrite_covariance") {
174 if (const auto value{parameter.as_double()}; value < 0.0) {
175 result.successful = false;
176 result.reason = "Covariance parameter must be non-negative";
177 RCLCPP_ERROR_STREAM(
178 get_logger(),
179 "Cannot change parameter '" << parameter.get_name() << "': " << result.reason);
180 break;
181 } else {
182 // Update the appropriate parameter in the config
183 update_config_double_parameter(parameter);
184 }
185 } else if (parameter.get_name() == "overwrite_covariance"){
186 config_.overwrite_covariance = parameter.as_bool();
187 } else if (parameter.get_name() == "adjust_pose"){
188 config_.adjust_pose = parameter.as_bool();
189 }
190 }
191
192 // If parameters were successfully updated, log the new configuration
193 if (result.successful) {
194 RCLCPP_DEBUG_STREAM(get_logger(), "Updated configuration: " << config_);
195 }
196
197 return result;
198 }
199
200 // Helper function to update a specific parameter in the config
201 void update_config_double_parameter(const rclcpp::Parameter & parameter) {
202 const std::string & name = parameter.get_name();
203 const double value = parameter.as_double();
204
205 if (name == "pose_covariance_x") {
206 config_.pose_covariance_x = value;
207 } else if (name == "pose_covariance_y") {
208 config_.pose_covariance_y = value;
209 } else if (name == "pose_covariance_z") {
210 config_.pose_covariance_z = value;
211 } else if (name == "pose_covariance_yaw") {
212 config_.pose_covariance_yaw = value;
213 } else if (name == "twist_covariance_x") {
214 config_.twist_covariance_x = value;
215 } else if (name == "twist_covariance_z") {
216 config_.twist_covariance_z = value;
217 } else if (name == "twist_covariance_yaw") {
218 config_.twist_covariance_yaw = value;
219 } else if (name == "x_offset") {
220 config_.x_offset = value;
221 } else if (name == "y_offset") {
222 config_.y_offset = value;
223 } else if (name == "yaw_offset") {
224 config_.yaw_offset = value;
225 }
226 }
227
228 // Set of valid parameter names for validation
229 std::unordered_set<std::string> valid_parameter_names_;
230};
231
232} // namespace carma_cooperative_perception
233
234#endif // CARMA_COOPERATIVE_PERCEPTION__SDSM_TO_DETECTION_LIST_COMPONENT_HPP_
rclcpp::Subscription< input_msg_type >::SharedPtr subscription_
carma_cooperative_perception_interfaces::msg::DetectionList output_msg_type
rcl_interfaces::msg::SetParametersResult update_parameters(const std::vector< rclcpp::Parameter > &parameters)
carma_v2x_msgs::msg::SensorDataSharingMessage input_msg_type
rclcpp::Subscription< std_msgs::msg::String >::SharedPtr georeference_subscription_
rclcpp::Publisher< output_msg_type >::SharedPtr publisher_
rclcpp::Subscription< rosgraph_msgs::msg::Clock >::SharedPtr cdasim_clock_sub_
auto handle_on_configure(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
auto sdsm_msg_callback(const input_msg_type &msg) const -> void
auto to_detection_list_msg(const carma_v2x_msgs::msg::SensorDataSharingMessage &sdsm, std::string_view georeference, bool is_simulation, const std::optional< SdsmToDetectionListConfig > &conversion_adjustment) -> carma_cooperative_perception_interfaces::msg::DetectionList
Converts a carma_v2x_msgs::msg::SensorDataSharingMessage (SDSM) to carma_cooperative_perception_inter...