85{
86 publisher_ = create_publisher<output_msg_type>(
"output/detections", 1);
87
90 const auto current_state{this->get_current_state().label()};
91
92 if (current_state == "active") {
94 } else {
95 RCLCPP_WARN(
96 this->get_logger(),
97 "Trying to receive message on the topic '%s', but the containing node is not activated. "
98 "Current node state: '%s'",
100 }
101 });
102
104 "input/georeference", 1, [this](std_msgs::msg::String::SharedPtr msg_ptr) {
105 const auto current_state{this->get_current_state().label()};
106
107 if (current_state == "active") {
109 } else {
110 RCLCPP_WARN(
111 this->get_logger(),
112 "Trying to receive message on the topic '%s', but the containing node is not activated. "
113 "Current node state: '%s'",
114 this->georeference_subscription_->get_topic_name(), current_state.c_str());
115 }
116 });
117
119 add_on_set_parameters_callback([this](const std::vector<rclcpp::Parameter> & parameters) {
120 rcl_interfaces::msg::SetParametersResult result;
121 result.successful = true;
122 result.reason = "success";
123
124 for (const auto & parameter : parameters) {
125 if (parameter.get_name() == "small_vehicle_motion_model") {
126 this->motion_model_mapping_.small_vehicle_model =
127 static_cast<std::uint8_t>(parameter.as_int());
128 } else if (parameter.get_name() == "large_vehicle_motion_model") {
129 this->motion_model_mapping_.large_vehicle_model =
130 static_cast<std::uint8_t>(parameter.as_int());
131 } else if (parameter.get_name() == "motorcycle_motion_model") {
132 this->motion_model_mapping_.motorcycle_model =
133 static_cast<std::uint8_t>(parameter.as_int());
134 } else if (parameter.get_name() == "pedestrian_motion_model") {
135 this->motion_model_mapping_.pedestrian_model =
136 static_cast<std::uint8_t>(parameter.as_int());
137 } else if (parameter.get_name() == "unknown_motion_model") {
138 this->motion_model_mapping_.unknown_model = static_cast<std::uint8_t>(parameter.as_int());
139 } else {
140 result.successful = false;
141 result.reason = "Unexpected parameter name '" + parameter.get_name() + '\'';
142 }
143 }
144
145 return result;
146 });
147
148
149
150
151
152
153
154
160
161 return carma_ros2_utils::CallbackReturn::SUCCESS;
162}
auto update_georeference(const std_msgs::msg::String &msg) -> void
typename input_msg_type::SharedPtr input_msg_shared_pointer
MotionModelMapping motion_model_mapping_
auto publish_as_detection_list(const input_msg_type &msg) const -> void
std::uint8_t large_vehicle_model
std::uint8_t unknown_model
std::uint8_t pedestrian_model
std::uint8_t motorcycle_model
std::uint8_t small_vehicle_model