31 {
32 CameraTrackingComponentConfig camera_tracking_component_config;
34 return false;
35 }
36 AINFO <<
"Camera Tracking Component config: "
37 << camera_tracking_component_config.DebugString();
38 output_channel_name_ = camera_tracking_component_config.output_channel_name();
39 writer_ =
40 node_->CreateWriter<onboard::SensorFrameMessage>(output_channel_name_);
41
42 sensor_manager_ = algorithm::SensorManager::Instance();
43
44 PluginParam plugin_param = camera_tracking_component_config.plugin_param();
45 std::string tracker_name = plugin_param.name();
46 camera_obstacle_tracker_.reset(
47 BaseObstacleTrackerRegisterer::GetInstanceByName(tracker_name));
48 if (nullptr == camera_obstacle_tracker_) {
49 AERROR <<
"Failed to get camera obstacle tracker instance.";
50 return false;
51 }
52
53 ObstacleTrackerInitOptions tracker_init_options;
54 tracker_init_options.config_path = plugin_param.config_path();
55 tracker_init_options.config_file = plugin_param.config_file();
56 tracker_init_options.image_width =
57 camera_tracking_component_config.image_width();
58 tracker_init_options.image_height =
59 camera_tracking_component_config.image_height();
60 tracker_init_options.gpu_id = camera_tracking_component_config.gpu_id();
61 if (!camera_obstacle_tracker_->Init(tracker_init_options)) {
62 AERROR <<
"Failed to init camera obstacle tracker.";
63 return false;
64 }
65 return true;
66}
bool GetProtoConfig(T *config) const
std::shared_ptr< Node > node_