15#ifndef CARMA_COOPERATIVE_PERCEPTION__SDSM_TO_DETECTION_LIST_COMPONENT_HPP_
16#define CARMA_COOPERATIVE_PERCEPTION__SDSM_TO_DETECTION_LIST_COMPONENT_HPP_
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>
36 using output_msg_type = carma_cooperative_perception_interfaces::msg::DetectionList;
40 -> carma_ros2_utils::CallbackReturn
override
71 [
this](
const std::vector<rclcpp::Parameter> & parameters) {
76 RCLCPP_INFO_STREAM(get_logger(),
"SdsmToDetectionListNode Configuration: " <<
config_);
78 return carma_ros2_utils::CallbackReturn::SUCCESS;
82 : CarmaLifecycleNode{options},
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; })}
94 valid_parameter_names_ = {
95 "overwrite_covariance",
99 "pose_covariance_yaw",
100 "twist_covariance_x",
101 "twist_covariance_z",
102 "twist_covariance_yaw",
113 std::optional<SdsmToDetectionListConfig> conversion_adjustment = std::nullopt;
114 if (config_.overwrite_covariance || config_.adjust_pose) {
115 conversion_adjustment = config_;
117 auto detection_list_msg{
119 conversion_adjustment)
124 const auto time_delta{now() - cdasim_time_.value()};
126 for (
auto & detection : detection_list_msg.detections) {
127 detection.header.stamp = rclcpp::Time(detection.header.stamp) + time_delta;
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());
145 std::optional<rclcpp::Time> cdasim_time_{std::nullopt};
147 std::string georeference_{
""};
152 OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_{
nullptr};
156 const std::vector<rclcpp::Parameter> & parameters)
158 rcl_interfaces::msg::SetParametersResult result;
159 result.successful =
true;
160 result.reason =
"success";
162 for (
const auto & parameter : parameters) {
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);
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";
179 "Cannot change parameter '" << parameter.get_name() <<
"': " << result.reason);
183 update_config_double_parameter(parameter);
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();
193 if (result.successful) {
194 RCLCPP_DEBUG_STREAM(get_logger(),
"Updated configuration: " << config_);
202 const std::string & name = parameter.get_name();
203 const double value = parameter.as_double();
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;
double twist_covariance_z
double pose_covariance_yaw
double twist_covariance_yaw
bool overwrite_covariance
double twist_covariance_x
void update_config_double_parameter(const rclcpp::Parameter ¶meter)
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 > ¶meters)
carma_v2x_msgs::msg::SensorDataSharingMessage input_msg_type
rclcpp::Subscription< std_msgs::msg::String >::SharedPtr georeference_subscription_
SdsmToDetectionListNode(const rclcpp::NodeOptions &options)
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
OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_
std::unordered_set< std::string > valid_parameter_names_
typename input_msg_type::SharedPtr input_msg_shared_pointer
SdsmToDetectionListConfig config_
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...