269 {
272 return false;
273 }
275 return false;
276 }
277
279 std::make_shared<apollo::cyber::proto::RoleAttributes>());
281
283 std::make_shared<apollo::cyber::proto::RoleAttributes>());
285
287 std::make_shared<apollo::cyber::proto::RoleAttributes>());
289
293
294 apollo_writer_0_ =
296 apollo_writer_1_ =
298 apollo_writer_2_ =
300#ifdef RCLCPP__RCLCPP_HPP_
301 ros_msg_subs_.push_back(
302 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
303 ros_node_, ros_topic_name_0)));
304 ros_msg_subs_.push_back(
305 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
306 ros_node_, ros_topic_name_1)));
307 ros_msg_subs_.push_back(
308 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
309 ros_node_, ros_topic_name_2)));
310 syncApproximate_ = std::make_shared<
311 message_filters::Synchronizer<approximate_sync_policy>>(
312 approximate_sync_policy(10),
313 *dynamic_cast<message_filters::Subscriber<InType0>*>(
314 ros_msg_subs_[0].get()),
315 *dynamic_cast<message_filters::Subscriber<InType1>*>(
316 ros_msg_subs_[1].get()),
317 *dynamic_cast<message_filters::Subscriber<InType2>*>(
318 ros_msg_subs_[2].get()));
319 syncApproximate_->registerCallback(
321 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
322 std::shared_ptr<InType2>>,
323 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
324 std::shared_ptr<OutType2>>>::TopicCallback,
325 this);
326
327 ros_spin_thread_ =
328 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
329#endif
330 return true;
331 }
std::atomic< bool > init_
std::unique_ptr< apollo::cyber::Node > cyber_node_
std::vector< std::shared_ptr< apollo::cyber::proto::RoleAttributes > > apollo_attrs_
ConverterConf converter_conf_
bool LoadConfig(ConverterConf *config)
optional string apollo_channel_name_2
optional string ros_topic_name_2
optional string apollo_channel_name_0
optional string apollo_channel_name_1
optional string ros_topic_name_0
optional string ros_topic_name_1