36 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
48 AERROR <<
"load config failed";
53 std::make_shared<apollo::cyber::proto::RoleAttributes>();
59 cyber_node_->template CreateWriter<OutType0>(*writer_attrs);
60#ifdef RCLCPP__RCLCPP_HPP_
61 ros_subscriptions_.push_back(
62 std::move(ros_node_->create_subscription<InType0>(
67 OutputTypes<std::shared_ptr<OutType0>>>::TopicCallback,
68 this, std::placeholders::_1))));
70 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
77 OutputTypes<std::shared_ptr<OutType0>>& output) = 0;
79#ifdef RCLCPP__RCLCPP_HPP_
81 void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
82 auto out = std::make_shared<OutType0>();
83 typename InType0::SharedPtr internal_in_prt =
84 std::make_shared<InType0>(*ros_msg0.get());
90 apollo_writer_0_->Write(out);
98 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>>>
101 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
102 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
118 std::make_shared<apollo::cyber::proto::RoleAttributes>());
122 std::make_shared<apollo::cyber::proto::RoleAttributes>());
131#ifdef RCLCPP__RCLCPP_HPP_
132 ros_subscriptions_.push_back(
133 std::move(ros_node_->create_subscription<InType0>(
134 ros_topic_name_0, 10,
139 std::shared_ptr<OutType1>>>::TopicCallback,
140 this, std::placeholders::_1))));
142 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
150 std::shared_ptr<OutType1>>& output) = 0;
152#ifdef RCLCPP__RCLCPP_HPP_
154 void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
155 auto out_0 = std::make_shared<OutType0>();
156 auto out_1 = std::make_shared<OutType1>();
157 typename InType0::SharedPtr internal_in_prt =
158 std::make_shared<InType0>(*ros_msg0.get());
163 std::make_tuple(out_0, out_1)};
164 this->
ConvertMsg(in_container, out_container);
165 apollo_writer_0_->Write(out_0);
166 apollo_writer_1_->Write(out_1);
175 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
178 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
179 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
180 std::shared_ptr<Writer<OutType2>> apollo_writer_2_ =
nullptr;
196 std::make_shared<apollo::cyber::proto::RoleAttributes>());
200 std::make_shared<apollo::cyber::proto::RoleAttributes>());
204 std::make_shared<apollo::cyber::proto::RoleAttributes>());
215#ifdef RCLCPP__RCLCPP_HPP_
216 ros_subscriptions_.push_back(
217 std::move(ros_node_->create_subscription<InType0>(
218 ros_topic_name_0, 10,
223 std::shared_ptr<OutType1>,
224 std::shared_ptr<OutType2>>>::TopicCallback,
225 this, std::placeholders::_1))));
227 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
235 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
236 std::shared_ptr<OutType2>>& output) = 0;
238#ifdef RCLCPP__RCLCPP_HPP_
240 void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
241 auto out_0 = std::make_shared<OutType0>();
242 auto out_1 = std::make_shared<OutType1>();
243 auto out_2 = std::make_shared<OutType2>();
244 typename InType0::SharedPtr internal_in_prt =
245 std::make_shared<InType0>(*ros_msg0.get());
250 std::shared_ptr<OutType2>>{
251 std::make_tuple(out_0, out_1, out_2)};
252 this->
ConvertMsg(in_container, out_container);
253 apollo_writer_0_->Write(out_0);
254 apollo_writer_1_->Write(out_1);
255 apollo_writer_2_->Write(out_2);
264 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
265 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>>
268 std::shared_ptr<Writer<OutType0>> apollo_writer_0_ =
nullptr;
269 std::shared_ptr<Writer<OutType1>> apollo_writer_1_ =
nullptr;
270 std::shared_ptr<Writer<OutType2>> apollo_writer_2_ =
nullptr;
271 std::shared_ptr<Writer<OutType3>> apollo_writer_3_ =
nullptr;
287 std::make_shared<apollo::cyber::proto::RoleAttributes>());
291 std::make_shared<apollo::cyber::proto::RoleAttributes>());
295 std::make_shared<apollo::cyber::proto::RoleAttributes>());
299 std::make_shared<apollo::cyber::proto::RoleAttributes>());
312#ifdef RCLCPP__RCLCPP_HPP_
313 ros_subscriptions_.push_back(
314 std::move(ros_node_->create_subscription<InType0>(
315 ros_topic_name_0, 10,
320 std::shared_ptr<OutType1>,
321 std::shared_ptr<OutType2>,
322 std::shared_ptr<OutType3>>>::TopicCallback,
323 this, std::placeholders::_1))));
325 std::make_shared<std::thread>(&MessageConverter::NodeSpin,
this);
333 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
334 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>&
337#ifdef RCLCPP__RCLCPP_HPP_
339 void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
340 auto out_0 = std::make_shared<OutType0>();
341 auto out_1 = std::make_shared<OutType1>();
342 auto out_2 = std::make_shared<OutType2>();
343 auto out_3 = std::make_shared<OutType3>();
344 typename InType0::SharedPtr internal_in_prt =
345 std::make_shared<InType0>(*ros_msg0.get());
350 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>{
351 std::make_tuple(out_0, out_1, out_2, out_3)};
352 this->
ConvertMsg(in_container, out_container);
353 apollo_writer_0_->Write(out_0);
354 apollo_writer_1_->Write(out_1);
355 apollo_writer_2_->Write(out_2);
356 apollo_writer_3_->Write(out_3);
virtual bool ConvertMsg(const std::shared_ptr< R0 > &ros_msg0, const std::shared_ptr< R1 > &ros_msg1, const std::shared_ptr< R2 > &ros_msg2, const std::shared_ptr< R3 > &ros_msg3, std::shared_ptr< M0 > &apollo_msg0, std::shared_ptr< M1 > &apollo_msg1, std::shared_ptr< M2 > &apollo_msg2, std::shared_ptr< M3 > &apollo_msg3)=0