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 > > > 模板类 参考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 > > > 继承关系图:
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 > > > 的协作图:

Public 成员函数

 ApolloRosMessageConverter ()
 
 ~ApolloRosMessageConverter () override
 
bool Init ()
 
- 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 > > &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>
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 > > >

在文件 convert_apollo_quadruple.h35 行定义.

构造及析构函数说明

◆ ApolloRosMessageConverter()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 >
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 > > >::ApolloRosMessageConverter ( )
inline

在文件 convert_apollo_quadruple.h40 行定义.

40{}

◆ ~ApolloRosMessageConverter()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 >
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 > > >::~ApolloRosMessageConverter ( )
inlineoverride

在文件 convert_apollo_quadruple.h41 行定义.

41{}

成员函数说明

◆ ConvertMsg()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 >
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 > > >::ConvertMsg ( InputTypes< std::shared_ptr< InType0 >, std::shared_ptr< InType1 >, std::shared_ptr< InType2 >, std::shared_ptr< InType3 > > &  input,
OutputTypes< std::shared_ptr< OutType0 > > &  output 
)
protectedpure virtual

◆ Init()

template<typename InType0 , typename InType1 , typename InType2 , typename InType3 , typename OutType0 >
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 > > >::Init ( )
inlinevirtual

重载 apollo::cyber::MessageConverter .

在文件 convert_apollo_quadruple.h43 行定义.

43 {
45 if (!init_.load()) {
46 return false;
47 }
49 return false;
50 }
51
52 apollo::cyber::ReaderConfig reader_cfg_0;
54
55 apollo::cyber::ReaderConfig reader_cfg_1;
57 auto apollo_reader_1 =
58 cyber_node_->template CreateReader<InType1>(reader_cfg_1);
59
60 apollo::cyber::ReaderConfig reader_cfg_2;
62 auto apollo_reader_2 =
63 cyber_node_->template CreateReader<InType2>(reader_cfg_2);
64
65 apollo::cyber::ReaderConfig reader_cfg_3;
67 auto apollo_reader_3 =
68 cyber_node_->template CreateReader<InType3>(reader_cfg_3);
69
70 std::string ros_topic_name_0 = converter_conf_.ros_topic_name_0();
71
72 auto apollo_blocker_1 =
73 blocker::BlockerManager::Instance()->GetBlocker<InType1>(
74 reader_cfg_1.channel_name);
75 auto apollo_blocker_2 =
76 blocker::BlockerManager::Instance()->GetBlocker<InType2>(
77 reader_cfg_2.channel_name);
78 auto apollo_blocker_3 =
79 blocker::BlockerManager::Instance()->GetBlocker<InType3>(
80 reader_cfg_3.channel_name);
81#ifdef RCLCPP__RCLCPP_HPP_
82 auto ros_publisher_0 =
83 ros_node_->create_publisher<OutType0>(ros_topic_name_0, 10);
84 ros_publishers_.push_back(std::move(ros_publisher_0));
85 auto func = [this, ros_publisher_0, apollo_blocker_1, apollo_blocker_2,
86 apollo_blocker_3](const std::shared_ptr<InType0> in) {
87#else
88 auto func = [this, apollo_blocker_1, apollo_blocker_2,
89 apollo_blocker_3](const std::shared_ptr<InType0> in) {
90#endif
91 auto out = std::make_shared<OutType0>();
92 if (!apollo_blocker_1->IsPublishedEmpty() &&
93 !apollo_blocker_2->IsPublishedEmpty() &&
94 !apollo_blocker_3->IsPublishedEmpty()) {
95 auto msg1 = apollo_blocker_1->GetLatestPublishedPtr();
96 auto msg2 = apollo_blocker_2->GetLatestPublishedPtr();
97 auto msg3 = apollo_blocker_3->GetLatestPublishedPtr();
98 auto in_container =
99 InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
100 std::shared_ptr<InType2>, std::shared_ptr<InType3>>{
101 std::make_tuple(in, msg1, msg2, msg3)};
102 auto out_container =
103 OutputTypes<std::shared_ptr<OutType0>>{std::make_tuple(out)};
104 this->ConvertMsg(in_container, out_container);
105#ifdef RCLCPP__RCLCPP_HPP_
106 ros_publisher_0->publish(*out);
107#endif
108 }
109 };
110 auto apollo_reader_0 =
111 cyber_node_->template CreateReader<InType0>(reader_cfg_0, func);
112 apollo_readers_.push_back(std::move(apollo_reader_0));
113 apollo_readers_.push_back(std::move(apollo_reader_1));
114 apollo_readers_.push_back(std::move(apollo_reader_2));
115 apollo_readers_.push_back(std::move(apollo_reader_3));
116
117 return true;
118 }
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 > > &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()

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