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

#include <convert_apollo_triple.h>

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

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 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 >, std::shared_ptr< OutType3 > > &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 OutType0, typename OutType1, typename OutType2, typename OutType3>
class apollo::cyber::ApolloRosMessageConverter< InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 > >, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 >, std::shared_ptr< OutType3 > > >

在文件 convert_apollo_triple.h332 行定义.

构造及析构函数说明

◆ ApolloRosMessageConverter()

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

在文件 convert_apollo_triple.h339 行定义.

339{}

◆ ~ApolloRosMessageConverter()

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

在文件 convert_apollo_triple.h340 行定义.

340{}

成员函数说明

◆ ConvertMsg()

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

◆ Init()

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

重载 apollo::cyber::MessageConverter .

在文件 convert_apollo_triple.h360 行定义.

360 {
362 if (!init_.load()) {
363 return false;
364 }
366 return false;
367 }
368
369 apollo::cyber::ReaderConfig reader_cfg_0;
371
372 apollo::cyber::ReaderConfig reader_cfg_1;
374 auto apollo_reader_1 =
375 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
376
377 apollo::cyber::ReaderConfig reader_cfg_2;
379 auto apollo_reader_2 =
380 cyber_node_->template CreateReader<InType2>(reader_cfg_2);
381
382 auto apollo_blocker_1 =
383 blocker::BlockerManager::Instance()->GetBlocker<InType1>(
384 reader_cfg_1.channel_name);
385 auto apollo_blocker_2 =
386 blocker::BlockerManager::Instance()->GetBlocker<InType2>(
387 reader_cfg_2.channel_name);
388
389 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
390 std::string ros_topic_name_1 = converter_conf_.ros_topic_name_1();
391 std::string ros_topic_name_2 = converter_conf_.ros_topic_name_2();
392 std::string ros_topic_name_3 = converter_conf_.ros_topic_name_3();
393
394#ifdef RCLCPP__RCLCPP_HPP_
395 auto ros_publisher_0 =
396 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
397 auto ros_publisher_1 =
398 ros_node_->create_publisher<OutType1>(ros_topic_name_1, 10);
399 auto ros_publisher_2 =
400 ros_node_->create_publisher<OutType2>(ros_topic_name_2, 10);
401 auto ros_publisher_3 =
402 ros_node_->create_publisher<OutType2>(ros_topic_name_3, 10);
403 ros_publishers_.push_back(std::move(ros_publisher_0));
404 ros_publishers_.push_back(std::move(ros_publisher_1));
405 ros_publishers_.push_back(std::move(ros_publisher_2));
406 ros_publishers_.push_back(std::move(ros_publisher_3));
407 auto func = [this, apollo_blocker_1, apollo_blocker_2, ros_publisher_0,
408 ros_publisher_1, ros_publisher_2,
409 ros_publisher_3](const std::shared_ptr<InType0> in) {
410#else
411 auto func = [this, apollo_blocker_1,
412 apollo_blocker_2](const std::shared_ptr<InType0> in) {
413#endif
414 if (!apollo_blocker_1->IsPublishedEmpty() &&
415 !apollo_blocker_2->IsPublishedEmpty()) {
416 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
417 auto msg2 = apollo_blocker_2->GetLatestPublishedPtr();
418 auto out_0 = std::make_shared<OutType0>();
419 auto out_1 = std::make_shared<OutType1>();
420 auto out_2 = std::make_shared<OutType2>();
421 auto out_3 = std::make_shared<OutType3>();
422 auto in_container =
423 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
424 std::shared_ptr<InType2>>{std::make_tuple(in, msg1, msg2)};
425 auto out_container =
426 OutputTypes<std::shared_ptr<OutType0>, std::shared_ptr<OutType1>,
427 std::shared_ptr<OutType2>, std::shared_ptr<OutType3>>{
428 std::make_tuple(out_0, out_1, out_2, out_3)};
429 this->ConvertMsg(in_container, out_container);
430#ifdef RCLCPP__RCLCPP_HPP_
431 ros_publisher_0->publish(*out_0);
432 ros_publisher_1->publish(*out_1);
433 ros_publisher_2->publish(*out_2);
434 ros_publisher_3->publish(*out_2);
435#endif
436 }
437 };
438 auto apollo_reader_0 =
439 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
440 apollo_readers_.push_back(std::move(apollo_reader_0));
441 apollo_readers_.push_back(std::move(apollo_reader_1));
442 apollo_readers_.push_back(std::move(apollo_reader_2));
443
444 return true;
445}
virtual bool ConvertMsg(InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 > > &input, OutputTypes< std::shared_ptr< OutType0 >, std::shared_ptr< OutType1 >, std::shared_ptr< OutType2 >, std::shared_ptr< OutType3 > > &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()

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