Apollo 10.0
自动驾驶开放平台
apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > > 模板类 参考abstract

#include <convert_apollo_quadruple.h>

类 apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > > 继承关系图:
apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > > 的协作图:

Public 成员函数

 ApolloRosMessageConverter ()
 
 ~ApolloRosMessageConverter () override
 
bool Init () override
 
- Public 成员函数 继承自 apollo::cyber::MessageConverter
 MessageConverter ()
 
virtual ~MessageConverter ()
 
bool IsInit () const
 

Protected 成员函数

virtual bool ConvertMsg (InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > &output)=0
 
- Protected 成员函数 继承自 apollo::cyber::MessageConverter
bool LoadConfig (ConverterConf *config)
 

额外继承的成员函数

- Protected 属性 继承自 apollo::cyber::MessageConverter
std::atomic< bool > init_
 
std::unique_ptr< apollo::cyber::Nodecyber_node_
 
std::vector< std::shared_ptr< apollo::cyber::proto::RoleAttributes > > apollo_attrs_
 
std::vector< std::shared_ptr< apollo::cyber::ReaderBase > > apollo_readers_
 
std::vector< std::shared_ptr< apollo::cyber::WriterBase > > apollo_writers_
 
const std::string node_name_ = "converter_base"
 
ConverterConf converter_conf_
 

详细描述

template<typename InType0, typename InType1, typename InType2, typename InType3, typename OutType0, typename OutType1, typename OutType2>
class apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > >

在文件 convert_apollo_quadruple.h251 行定义.

构造及析构函数说明

◆ ApolloRosMessageConverter()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 , typename OutType1 , typename OutType2 >
apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > >::ApolloRosMessageConverter ( )
inline

在文件 convert_apollo_quadruple.h257 行定义.

257{}

◆ ~ApolloRosMessageConverter()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 , typename OutType1 , typename OutType2 >
apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > >::~ApolloRosMessageConverter ( )
inlineoverride

在文件 convert_apollo_quadruple.h258 行定义.

258{}

成员函数说明

◆ ConvertMsg()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 , typename OutType1 , typename OutType2 >
virtual bool apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > >::ConvertMsg ( InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > > &  input,
OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > &  output 
)
protectedpure virtual

◆ Init()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 , typename OutType1 , typename OutType2 >
bool apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > >::Init ( )
overridevirtual

重载 apollo::cyber::MessageConverter .

在文件 convert_apollo_quadruple.h277 行定义.

277 {
279 if (!init_.load()) {
280 return false;
281 }
283 return false;
284 }
285
286 apollo::cyber::ReaderConfig reader_cfg_0;
288
289 apollo::cyber::ReaderConfig reader_cfg_1;
291 auto apollo_reader_1 =
292 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
293
294 apollo::cyber::ReaderConfig reader_cfg_2;
296 auto apollo_reader_2 =
297 cyber_node_->template CreateReader<InType2>(reader_cfg_2);
298
299 apollo::cyber::ReaderConfig reader_cfg_3;
301 auto apollo_reader_3 =
302 cyber_node_->template CreateReader<InType3>(reader_cfg_3);
303
304 auto apollo_blocker_1 =
305 blocker::BlockerManager::Instance()->GetBlocker<InType1>(
306 reader_cfg_1.channel_name);
307 auto apollo_blocker_2 =
308 blocker::BlockerManager::Instance()->GetBlocker<InType2>(
309 reader_cfg_2.channel_name);
310 auto apollo_blocker_3 =
311 blocker::BlockerManager::Instance()->GetBlocker<InType3>(
312 reader_cfg_3.channel_name);
313
314 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
315 std::string ros_topic_name_1 = converter_conf_.ros_topic_name_1();
316 std::string ros_topic_name_2 = converter_conf_.ros_topic_name_2();
317
318#ifdef RCLCPP__RCLCPP_HPP_
319 auto ros_publisher_0 =
320 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
321 auto ros_publisher_1 =
322 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
323 auto ros_publisher_2 =
324 ros_node_->create_publisher<OutType2>(ros_topic_name_2, 10);
325 ros_publishers_.push_back(std::move(ros_publisher_0));
326 ros_publishers_.push_back(std::move(ros_publisher_1));
327 ros_publishers_.push_back(std::move(ros_publisher_2));
328 auto func = [this, apollo_blocker_1, apollo_blocker_2, apollo_blocker_3,
329 ros_publisher_0, ros_publisher_1,
330 ros_publisher_2](const std::shared_ptr<InType0> in) {
331#else
332 auto func = [this, apollo_blocker_1, apollo_blocker_2,
333 apollo_blocker_3](const std::shared_ptr<InType0> in) {
334#endif
335 if (!apollo_blocker_1->IsPublishedEmpty() &&
336 !apollo_blocker_1->IsPublishedEmpty() &&
337 !apollo_blocker_1->IsPublishedEmpty()) {
338 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
339 auto msg2 = apollo_blocker_2->GetLatestPublishedPtr();
340 auto msg3 = apollo_blocker_3->GetLatestPublishedPtr();
341 auto out_0 = std::make_shared<OutType0>();
342 auto out_1 = std::make_shared<OutType1>();
343 auto out_2 = std::make_shared<OutType2>();
344 auto in_container =
345 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
346 std::shared_ptr<InType2>, std::shared_ptr<InType3>>{
347 std::make_tuple(in, msg1, msg2, msg3)};
348 auto out_container =
349 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
350 std::shared_ptr<OutType2>>{
351 std::make_tuple(out_0, out_1, out_2)};
352 this->ConvertMsg(in_container, out_container);
353#ifdef RCLCPP__RCLCPP_HPP_
354 ros_publisher_0->publish(*out_0);
355 ros_publisher_1->publish(*out_1);
356 ros_publisher_2->publish(*out_2);
357#endif
358 }
359 };
360 auto apollo_reader_0 =
361 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
362 apollo_readers_.push_back(std::move(apollo_reader_0));
363 apollo_readers_.push_back(std::move(apollo_reader_1));
364 apollo_readers_.push_back(std::move(apollo_reader_2));
365 apollo_readers_.push_back(std::move(apollo_reader_3));
366
367 return true;
368}
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 > > &output)=0
std::unique_ptr< apollo::cyber::Node > cyber_node_
std::vector< std::shared_ptr< apollo::cyber::ReaderBase > > apollo_readers_
bool LoadConfig(ConverterConf *config)
static const std::shared_ptr< BlockerManager > & Instance()

该类的文档由以下文件生成: