164 {
167 return false;
168 }
170 return false;
171 }
172
174 std::make_shared<apollo::cyber::proto::RoleAttributes>());
176
178 std::make_shared<apollo::cyber::proto::RoleAttributes>());
180
185
186 apollo_writer_0_ =
188 apollo_writer_1_ =
190#ifdef RCLCPP__RCLCPP_HPP_
191 ros_msg_subs_.push_back(
192 std::move(std::make_shared<message_filters::Subscriber<InType0>>(
193 ros_node_, ros_topic_name_0)));
194 ros_msg_subs_.push_back(
195 std::move(std::make_shared<message_filters::Subscriber<InType1>>(
196 ros_node_, ros_topic_name_1)));
197 ros_msg_subs_.push_back(
198 std::move(std::make_shared<message_filters::Subscriber<InType2>>(
199 ros_node_, ros_topic_name_2)));
200 ros_msg_subs_.push_back(
201 std::move(std::make_shared<message_filters::Subscriber<InType3>>(
202 ros_node_, ros_topic_name_3)));
203 syncApproximate_ = std::make_shared<
204 message_filters::Synchronizer<approximate_sync_policy>>(
205 approximate_sync_policy(10),
206 *dynamic_cast<message_filters::Subscriber<InType0>*>(
207 ros_msg_subs_[0].get()),
208 *dynamic_cast<message_filters::Subscriber<InType1>*>(
209 ros_msg_subs_[1].get()),
210 *dynamic_cast<message_filters::Subscriber<InType2>*>(
211 ros_msg_subs_[2].get()),
212 *dynamic_cast<message_filters::Subscriber<InType3>*>(
213 ros_msg_subs_[3].get()));
214 syncApproximate_->registerCallback(
216 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
217 std::shared_ptr<InType2>, std::shared_ptr<InType3>>,
218 OutputTypes<std::shared_ptr<OutType0>,
219 std::shared_ptr<OutType1>>>::TopicCallback,
220 this);
221
222 ros_spin_thread_ =
223 std::make_shared<std::thread>(&MessageConverter::NodeSpin, this);
224#endif
225 return true;
226 }
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 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