Apollo 10.0
自动驾驶开放平台
apollo::perception::camera::MotionServiceComponent类 参考final

#include <motion_service_component.h>

类 apollo::perception::camera::MotionServiceComponent 继承关系图:
apollo::perception::camera::MotionServiceComponent 的协作图:

Public 成员函数

 MotionServiceComponent ()=default
 
virtual ~MotionServiceComponent ()
 
bool Init () override
 
bool GetMotionInformation (double timestamp, base::VehicleStatus *vs)
 
base::MotionBuffer GetMotionBuffer ()
 
double GetLatestTimestamp ()
 
- Public 成员函数 继承自 apollo::cyber::Component< M0, M1, M2, M3 >
 Component ()
 
 ~Component () override
 
bool Initialize (const ComponentConfig &config) override
 init the component by protobuf object.
 
bool Process (const std::shared_ptr< M0 > &msg0, const std::shared_ptr< M1 > &msg1, const std::shared_ptr< M2 > &msg2, const std::shared_ptr< M3 > &msg3)
 
- Public 成员函数 继承自 apollo::cyber::ComponentBase
virtual ~ComponentBase ()
 
virtual bool Initialize (const TimerComponentConfig &config)
 
virtual void Shutdown ()
 
template<typename T >
bool GetProtoConfig (T *config) const
 

额外继承的成员函数

- Public 类型 继承自 apollo::cyber::ComponentBase
template<typename M >
using Reader = cyber::Reader< M >
 
- Protected 成员函数 继承自 apollo::cyber::ComponentBase
virtual void Clear ()
 
const std::string & ConfigFilePath () const
 
void LoadConfigFiles (const ComponentConfig &config)
 
void LoadConfigFiles (const TimerComponentConfig &config)
 
- Protected 属性 继承自 apollo::cyber::ComponentBase
std::atomic< bool > is_shutdown_ = {false}
 
std::shared_ptr< Nodenode_ = nullptr
 
std::string config_file_path_ = ""
 
std::vector< std::shared_ptr< ReaderBase > > readers_
 

详细描述

在文件 motion_service_component.h44 行定义.

构造及析构函数说明

◆ MotionServiceComponent()

apollo::perception::camera::MotionServiceComponent::MotionServiceComponent ( )
default

◆ ~MotionServiceComponent()

virtual apollo::perception::camera::MotionServiceComponent::~MotionServiceComponent ( )
inlinevirtual

在文件 motion_service_component.h47 行定义.

47{ delete vehicle_planemotion_; }

成员函数说明

◆ GetLatestTimestamp()

double apollo::perception::camera::MotionServiceComponent::GetLatestTimestamp ( )

在文件 motion_service_component.cc222 行定义.

222 {
223 return pre_camera_timestamp_;
224}

◆ GetMotionBuffer()

base::MotionBuffer apollo::perception::camera::MotionServiceComponent::GetMotionBuffer ( )

在文件 motion_service_component.cc217 行定义.

217 {
218 std::lock_guard<std::mutex> lock(motion_mutex_);
219 return vehicle_planemotion_->get_buffer();
220}

◆ GetMotionInformation()

bool apollo::perception::camera::MotionServiceComponent::GetMotionInformation ( double  timestamp,
base::VehicleStatus vs 
)

在文件 motion_service_component.cc227 行定义.

228 {
229 return vehicle_planemotion_->find_motion_with_timestamp(timestamp, vs);
230}
bool find_motion_with_timestamp(double timestamp, base::VehicleStatus *vs)

◆ Init()

bool apollo::perception::camera::MotionServiceComponent::Init ( )
overridevirtual

实现了 apollo::cyber::ComponentBase.

在文件 motion_service_component.cc33 行定义.

33 {
34 AINFO << "start to init MotionService.";
35 vehicle_planemotion_ = new PlaneMotion(motion_buffer_size_);
36
37 // the macro READ_CONF would return cyber::FAIL if config not exists
39 if (!GetProtoConfig(&motion_service_param)) {
40 AINFO << "load lane detection component proto param failed";
41 return false;
42 }
43
44 std::string camera_names_str = motion_service_param.camera_names();
45 boost::algorithm::split(camera_names_, camera_names_str,
46 boost::algorithm::is_any_of(","));
47
48 std::string input_camera_channel_names_str =
49 motion_service_param.input_camera_channel_names();
50 boost::algorithm::split(input_camera_channel_names_,
51 input_camera_channel_names_str,
52 boost::algorithm::is_any_of(","));
53 if (input_camera_channel_names_.size() != camera_names_.size()) {
54 AERROR << "wrong input_camera_channel_names_.size(): "
55 << input_camera_channel_names_.size();
56 return cyber::FAIL;
57 }
58
59 // initialize image listener
60 const std::string &channel_name_img = input_camera_channel_names_[0];
61 const std::string &camera_name = camera_names_[0];
62 std::function<void(const ImageMsgType &)> camera_callback =
63 std::bind(&MotionServiceComponent::OnReceiveImage, this,
64 std::placeholders::_1, camera_name);
65 auto camera_reader = node_->CreateReader(channel_name_img, camera_callback);
66
67 // initialize localization listener
68 const std::string &channel_name_local =
69 motion_service_param.input_localization_channel_name();
70 std::function<void(const LocalizationMsgType &)> localization_callback =
71 std::bind(&MotionServiceComponent::OnLocalization, this,
72 std::placeholders::_1);
73 auto localization_reader =
74 node_->CreateReader(channel_name_local, localization_callback);
75
76 // initialize writer to output channel
77 writer_ = node_->CreateWriter<MotionService>(
78 motion_service_param.output_topic_channel_name());
79 AINFO << "init MotionService success.";
80 return true;
81}
bool GetProtoConfig(T *config) const
std::shared_ptr< Node > node_
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
std::shared_ptr< localization::LocalizationEstimate > LocalizationMsgType
std::shared_ptr< apollo::drivers::Image > ImageMsgType

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