23 #include "boost/circular_buffer.hpp" 33 namespace perception {
43 std::map<std::string, int>* image_borders_size =
nullptr;
53 std::string Name()
const;
55 bool UpdateCameraSelection(
const CarPose& pose,
57 std::vector<base::TrafficLightPtr>* lights);
59 bool SyncInformation(
const double ts,
const std::string& camera_name);
60 bool UpdateLightsProjection(
const CarPose& pose,
62 const std::string& camera_name,
63 std::vector<base::TrafficLightPtr>* lights);
65 bool SetCameraWorkingFlag(
const std::string& camera_name,
bool is_working);
66 bool GetCameraWorkingFlag(
const std::string& camera_name,
67 bool* is_working)
const;
70 return projection_.getCameraNamesByDescendingFocalLen();
72 bool GetAlllightsOutsideFlag()
const;
76 std::vector<base::TrafficLightPtrs>* lights_on_image_array,
77 std::vector<base::TrafficLightPtrs>* lights_outside_image_array,
81 bool ProjectLights(
const CarPose& pose,
const std::string& camera_name,
82 std::vector<base::TrafficLightPtr>* lights,
86 bool ProjectLightsAndSelectCamera(
const CarPose& pose,
88 std::string* selected_camera_name,
89 std::vector<base::TrafficLightPtr>* lights);
91 std::string GetMinFocalLenWorkingCameraName()
const;
92 std::string GetMaxFocalLenWorkingCameraName()
const;
96 double last_pub_img_ts_ = 0.0;
99 std::pair<double, std::string> selected_camera_name_;
100 std::map<std::string, bool> camera_is_working_flags_;
101 double sync_interval_seconds_ = 0.1;
102 size_t num_cameras_ = 0;
103 std::vector<base::TrafficLightPtrs> lights_on_image_array_;
104 std::vector<base::TrafficLightPtrs> lights_outside_image_array_;
107 bool projections_outside_all_images_ =
false;
Definition: base_init_options.h:24
const std::vector< std::string > & GetCameraNamesByDescendingFocalLen() const
Definition: tl_preprocessor.h:69
float sync_interval_seconds
Definition: tl_preprocessor.h:38
Definition: multi_camera_projection.h:41
int gpu_id
Definition: tl_preprocessor.h:37
Definition: tl_preprocessor.h:42
std::vector< TrafficLightPtr > TrafficLightPtrs
Definition: traffic_light.h:89
Definition: tl_preprocessor.h:46
Definition: tl_preprocessor.h:36
std::vector< std::string > camera_names
Definition: tl_preprocessor.h:39