290 {
293 return false;
294 }
296 return false;
297 }
298
300 std::make_shared<apollo::cyber::proto::RoleAttributes>());
302
304 std::make_shared<apollo::cyber::proto::RoleAttributes>());
306
308 std::make_shared<apollo::cyber::proto::RoleAttributes>());
310
315
316 apollo_writer_0_ =
318 apollo_writer_1_ =
320 apollo_writer_2_ =
322#ifdef RCLCPP__RCLCPP_HPP_
323 ros_msg_subs_.push_back(
324 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
325 ros_node_, ros_topic_name_0)));
326 ros_msg_subs_.push_back(
327 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
328 ros_node_, ros_topic_name_1)));
329 ros_msg_subs_.push_back(
330 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
331 ros_node_, ros_topic_name_2)));
332 ros_msg_subs_.push_back(
333 std::move(std::make_shared<message_filters::Subscriber<InType3>>(
334 ros_node_, ros_topic_name_3)));
335 syncApproximate_ = std::make_shared<
336 message_filters::Synchronizer<approximate_sync_policy>>(
337 approximate_sync_policy(10),
338 *dynamic_cast<message_filters::Subscriber<InType0>*>(
339 ros_msg_subs_[0].get()),
340 *dynamic_cast<message_filters::Subscriber<InType1>*>(
341 ros_msg_subs_[1].get()),
342 *dynamic_cast<message_filters::Subscriber<InType2>*>(
343 ros_msg_subs_[2].get()),
344 *dynamic_cast<message_filters::Subscriber<InType3>*>(
345 ros_msg_subs_[3].get()));
346 syncApproximate_->registerCallback(
348 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
349 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
350 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
351 std::shared_ptr<OutType2>>>::TopicCallback,
352 this);
353
354 ros_spin_thread_ =
355 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
356#endif
357 return true;
358 }
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_3
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