Apollo  6.0
Open source self driving car software
multicue_obstacle_transformer.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the License);
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an AS IS BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 #pragma once
17 
18 #include <algorithm>
19 #include <map>
20 #include <string>
21 #include <utility>
22 #include <vector>
23 
26 #include "modules/perception/camera/lib/obstacle/transformer/multicue/proto/multicue.pb.h"
27 
28 namespace apollo {
29 namespace perception {
30 namespace camera {
31 
33  public:
35  mapper_ = new ObjMapper;
36  }
37 
39  delete mapper_;
40  mapper_ = nullptr;
41  }
42  bool Init(const ObstacleTransformerInitOptions &options =
44 
45  // @brief: transform 2D detections to 3D bounding box
46  // @param [in]: frame
47  // @param [out]: frame
48  bool Transform(const ObstacleTransformerOptions &options,
49  CameraFrame *frame) override;
50 
51  std::string Name() const override;
52 
53  private:
54  void SetObjMapperOptions(base::ObjectPtr obj, Eigen::Matrix3f camera_k_matrix,
55  int width_image, int height_image,
56  ObjMapperOptions *obj_mapper_options,
57  float *theta_ray);
58  int MatchTemplates(base::ObjectSubType sub_type, float *dimension_hwl);
59  void FillResults(float object_center[3], float dimension_hwl[3],
60  float rotation_y, Eigen::Affine3d camera2world_pose,
61  float theta_ray, base::ObjectPtr obj);
62 
63  private:
64  multicue::MulticueParam multicue_param_;
65  int image_width_ = 0;
66  int image_height_ = 0;
67  ObjMapper *mapper_ = nullptr;
68 
69  protected:
71 };
72 
73 } // namespace camera
74 } // namespace perception
75 } // namespace apollo
Definition: base_obstacle_transformer.h:31
Definition: obj_mapper.h:66
Definition: camera_frame.h:33
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
virtual ~MultiCueObstacleTransformer()
Definition: multicue_obstacle_transformer.h:38
Eigen::Matrix3f Matrix3f
Definition: base_map_fwd.h:27
Definition: object_template_manager.h:49
bool Init(const ObstacleTransformerInitOptions &options=ObstacleTransformerInitOptions()) override
MultiCueObstacleTransformer()
Definition: multicue_obstacle_transformer.h:34
Definition: multicue_obstacle_transformer.h:32
Definition: base_obstacle_transformer.h:29
ObjectTemplateManager * object_template_manager_
Definition: multicue_obstacle_transformer.h:70
bool Transform(const ObstacleTransformerOptions &options, CameraFrame *frame) override
Definition: base_obstacle_transformer.h:38
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
ObjectSubType
Definition: object_types.h:63
std::shared_ptr< Object > ObjectPtr
Definition: object.h:123