182 {
185 return false;
186 }
188 return false;
189 }
190
193
197
198#ifdef RCLCPP__RCLCPP_HPP_
199 auto ros_publisher_0 =
200 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
201 auto ros_publisher_1 =
202 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
203 auto ros_publisher_2 =
204 ros_node_->create_publisher<OutType2>(ros_topic_name_2, 10);
205 ros_publishers_.push_back(std::move(ros_publisher_0));
206 ros_publishers_.push_back(std::move(ros_publisher_1));
207 ros_publishers_.push_back(std::move(ros_publisher_2));
208 auto func = [
this, ros_publisher_0, ros_publisher_1,
209 ros_publisher_2](const std::shared_ptr<InType0> in) {
210#else
211 auto func = [
this](
const std::shared_ptr<InType0> in) {
212#endif
213 auto out_0 = std::make_shared<OutType0>();
214 auto out_1 = std::make_shared<OutType1>();
215 auto out_2 = std::make_shared<OutType2>();
216 auto in_container =
217 InputTypes<std::shared_ptr<InType0>>{std::make_tuple(in)};
218 auto out_container =
219 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
220 std::shared_ptr<OutType2>>{
221 std::make_tuple(out_0, out_1, out_2)};
222 this->
ConvertMsg(in_container, out_container);
223#ifdef RCLCPP__RCLCPP_HPP_
224 ros_publisher_0->publish(*out_0);
225 ros_publisher_1->publish(*out_1);
226 ros_publisher_2->publish(*out_2);
227#endif
228 };
229 auto apollo_reader_0 =
230 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
232
233 return true;
234}
std::atomic< bool > init_
std::unique_ptr< apollo::cyber::Node > cyber_node_
std::vector< std::shared_ptr< apollo::cyber::ReaderBase > > apollo_readers_
ConverterConf converter_conf_
bool LoadConfig(ConverterConf *config)
optional string ros_topic_name_2
optional string apollo_channel_name_0
optional string ros_topic_name_0
optional string ros_topic_name_1