Apollo 10.0
自动驾驶开放平台
apollo::third_party_perception::conversion_mobileye 命名空间参考

apollo::third_party_perception 更多...

类型定义

using Point = apollo::common::Point3D
 

函数

PerceptionObstacles MobileyeToPerceptionObstacles (const Mobileye &mobileye, const LocalizationEstimate &localization, const Chassis &chassis)
 

详细描述

类型定义说明

◆ Point

函数说明

◆ MobileyeToPerceptionObstacles()

apollo::perception::PerceptionObstacles apollo::third_party_perception::conversion_mobileye::MobileyeToPerceptionObstacles ( const Mobileye mobileye,
const LocalizationEstimate localization,
const Chassis chassis 
)

在文件 conversion_mobileye.cc48 行定义.

50 {
51 PerceptionObstacles obstacles;
52 // retrieve position and velocity of the main vehicle from the localization
53 // position
54 std::map<std::int32_t, apollo::hdmap::LaneBoundaryType_Type>
55 lane_conversion_map = {{0, apollo::hdmap::LaneBoundaryType::DOTTED_YELLOW},
62
63 obstacles.mutable_header()->CopyFrom(mobileye.header());
64
65 // Fullfill lane_type information
66 std::int32_t mob_left_lane_type = mobileye.lka_766().lane_type();
67 std::int32_t mob_right_lane_type = mobileye.lka_768().lane_type();
68
69 obstacles.mutable_lane_marker()->mutable_left_lane_marker()->set_lane_type(
70 lane_conversion_map[mob_left_lane_type]);
71 obstacles.mutable_lane_marker()->mutable_right_lane_marker()->set_lane_type(
72 lane_conversion_map[mob_right_lane_type]);
73
74 obstacles.mutable_lane_marker()->mutable_left_lane_marker()->set_quality(
75 mobileye.lka_766().quality() / 4.0);
76 obstacles.mutable_lane_marker()->mutable_left_lane_marker()->set_model_degree(
77 mobileye.lka_766().model_degree());
78
79 // Convert everything to FLU
80 obstacles.mutable_lane_marker()->mutable_left_lane_marker()->set_c0_position(
81 -mobileye.lka_766().position());
82 obstacles.mutable_lane_marker()
83 ->mutable_left_lane_marker()
84 ->set_c1_heading_angle(-mobileye.lka_767().heading_angle());
85 obstacles.mutable_lane_marker()->mutable_left_lane_marker()->set_c2_curvature(
86 -mobileye.lka_766().curvature());
87 obstacles.mutable_lane_marker()
88 ->mutable_left_lane_marker()
89 ->set_c3_curvature_derivative(-mobileye.lka_766().curvature_derivative());
90 obstacles.mutable_lane_marker()->mutable_left_lane_marker()->set_view_range(
91 mobileye.lka_767().view_range());
92
93 obstacles.mutable_lane_marker()->mutable_right_lane_marker()->set_quality(
94 mobileye.lka_768().quality() / 4.0);
95 obstacles.mutable_lane_marker()
96 ->mutable_right_lane_marker()
97 ->set_model_degree(mobileye.lka_768().model_degree());
98 obstacles.mutable_lane_marker()->mutable_right_lane_marker()->set_c0_position(
99 -mobileye.lka_768().position());
100 obstacles.mutable_lane_marker()
101 ->mutable_right_lane_marker()
102 ->set_c1_heading_angle(-mobileye.lka_769().heading_angle());
103 obstacles.mutable_lane_marker()
104 ->mutable_right_lane_marker()
105 ->set_c2_curvature(-mobileye.lka_768().curvature());
106 obstacles.mutable_lane_marker()
107 ->mutable_right_lane_marker()
108 ->set_c3_curvature_derivative(-mobileye.lka_768().curvature_derivative());
109 obstacles.mutable_lane_marker()->mutable_right_lane_marker()->set_view_range(
110 mobileye.lka_769().view_range());
111
112 double adc_x = localization.pose().position().x();
113 double adc_y = localization.pose().position().y();
114 double adc_z = localization.pose().position().z();
115 // heading
116 auto adc_quaternion = localization.pose().orientation();
117 double adc_theta = GetAngleFromQuaternion(adc_quaternion);
118 // velocity
119 double adc_vx = localization.pose().linear_velocity().x();
120 double adc_vy = localization.pose().linear_velocity().y();
121 double adc_velocity = Speed(adc_vx, adc_vy);
122
123 for (int index = 0; index < mobileye.details_738().num_obstacles() &&
124 index < mobileye.details_739_size();
125 ++index) {
126 auto* mob = obstacles.add_perception_obstacle();
127 const auto& data_739 = mobileye.details_739(index);
128 int mob_id = data_739.obstacle_id() + FLAGS_mobileye_id_offset;
129 double mob_x = data_739.obstacle_pos_x();
130 double mob_y = -data_739.obstacle_pos_y();
131 double mob_vel_x = data_739.obstacle_rel_vel_x();
132 int mob_type = data_739.obstacle_type();
133
134 double mob_l = 0.0;
135 double mob_w = 0.0;
136 if (mobileye.details_73a_size() <= index) {
137 mob_l = GetDefaultObjectLength(mob_type);
138 mob_w = GetDefaultObjectWidth(mob_type);
139 } else {
140 if (mobileye.details_73a(index).obstacle_length() >
141 FLAGS_max_mobileye_obstacle_length) {
142 mob_l = GetDefaultObjectLength(mob_type);
143 } else {
144 mob_l = mobileye.details_73a(index).obstacle_length();
145 }
146
147 if (mobileye.details_73a(index).obstacle_width() >
148 FLAGS_max_mobileye_obstacle_width) {
149 mob_w = GetDefaultObjectWidth(mob_type);
150 } else {
151 mob_w = mobileye.details_73a(index).obstacle_width();
152 }
153 }
154
155 mob_x += FLAGS_mobileye_pos_adjust; // offset: imu <-> mobileye
156 mob_x += mob_l / 2.0; // make x the middle point of the vehicle.
157
158 Point xy_point = SLtoXY(mob_x, mob_y, adc_theta);
159
160 // TODO(QiL) : Clean this up after data collection and validation
161 double converted_x = 0.0;
162 double converted_y = 0.0;
163 double converted_speed = 0.0;
164 double converted_vx = 0.0;
165 double converted_vy = 0.0;
166
167 double path_c1 = 0.0;
168 double path_c2 = 0.0;
169 double path_c3 = 0.0;
170
171 if (obstacles.lane_marker().left_lane_marker().quality() >=
172 obstacles.lane_marker().right_lane_marker().quality()) {
173 path_c1 = obstacles.lane_marker().left_lane_marker().c1_heading_angle();
174 path_c2 = obstacles.lane_marker().left_lane_marker().c2_curvature();
175 path_c3 =
177 } else {
178 path_c1 = obstacles.lane_marker().right_lane_marker().c1_heading_angle();
179 path_c2 = obstacles.lane_marker().right_lane_marker().c2_curvature();
180 path_c3 =
182 }
183
184 if (!FLAGS_use_navigation_mode) {
185 converted_x = adc_x + xy_point.x();
186 converted_y = adc_y + xy_point.y();
187 mob->set_theta(GetNearestLaneHeading(converted_x, converted_y, adc_z));
188 converted_speed = adc_velocity + mob_vel_x;
189 converted_vx = converted_speed * std::cos(mob->theta());
190 converted_vy = converted_speed * std::sin(mob->theta());
191 } else {
192 converted_x = mobileye.details_739(index).obstacle_pos_x() +
193 FLAGS_mobileye_pos_adjust;
194 converted_y = mobileye.details_739(index).obstacle_pos_y();
195 converted_vx = mob_vel_x + chassis.speed_mps();
196 converted_vy = 0.0;
197
198 if (mobileye.details_73b_size() <= index) {
199 mob->set_theta(0.0);
200 } else {
201 if (!FLAGS_overwrite_mobileye_theta) {
202 mob->set_theta(mobileye.details_73b(index).obstacle_angle() / 180 *
203 M_PI);
204 } else {
205 double nearest_lane_heading =
206 converted_vx > 0
207 ? std::atan2(3 * path_c3 * converted_x * converted_x +
208 2 * path_c2 * converted_x + path_c1,
209 1)
210 : std::atan2(3 * path_c3 * converted_x * converted_x +
211 2 * path_c2 * converted_x + path_c1,
212 1) +
213 M_PI;
214 AINFO << "nearest lane heading is" << nearest_lane_heading;
215 mob->set_theta(nearest_lane_heading);
216 }
217 }
218 }
219
220 mob->set_id(mob_id);
221 mob->mutable_position()->set_x(converted_x);
222 mob->mutable_position()->set_y(converted_y);
223
224 switch (mob_type) {
225 case 0:
226 case 1: {
227 mob->set_type(PerceptionObstacle::VEHICLE); // VEHICLE
228 break;
229 }
230 case 2:
231 case 4: {
232 mob->set_type(PerceptionObstacle::BICYCLE); // BIKE
233 break;
234 }
235 case 3: {
236 mob->set_type(PerceptionObstacle::PEDESTRIAN); // PED
237 break;
238 }
239 default: {
240 mob->set_type(PerceptionObstacle::UNKNOWN); // UNKNOWN
241 break;
242 }
243 }
244
245 mob->mutable_velocity()->set_x(converted_vx);
246 mob->mutable_velocity()->set_y(converted_vy);
247 mob->set_length(mob_l);
248 mob->set_width(mob_w);
249 mob->set_height(FLAGS_default_height);
250
251 mob->clear_polygon_point();
252
253 // create polygon
254 FillPerceptionPolygon(mob, mob->position().x(), mob->position().y(),
255 mob->position().z(), mob->length(), mob->width(),
256 mob->height(), mob->theta());
257
258 mob->set_confidence(0.5);
259 }
260
261 return obstacles;
262}
#define AINFO
Definition log.h:42
apollo::common::Point3D Point
void FillPerceptionPolygon(PerceptionObstacle *const perception_obstacle, const double mid_x, const double mid_y, const double mid_z, const double length, const double width, const double height, const double heading)
double GetDefaultObjectLength(const int object_type)
double GetAngleFromQuaternion(const Quaternion quaternion)
Point SLtoXY(const Point &point, const double theta)
double GetNearestLaneHeading(const PointENU &point_enu)
double GetDefaultObjectWidth(const int object_type)
Definition future.h:29
optional float speed_mps
Definition chassis.proto:70
optional double obstacle_length
optional int32 lane_type
optional double curvature
optional double curvature_derivative
optional int32 model_degree
optional double position
optional double heading_angle
optional double view_range
optional int32 model_degree
optional int32 lane_type
Definition mobileye.proto:8
optional double position
optional double curvature
optional double curvature_derivative
optional int32 quality
Definition mobileye.proto:9
optional double view_range
optional double heading_angle
repeated Details_73a details_73a
optional Details_738 details_738
optional apollo::common::Header header
optional Lka_768 lka_768
optional Lka_767 lka_767
repeated Details_739 details_739
optional Lka_766 lka_766
repeated Details_73b details_73b
optional Lka_769 lka_769
optional apollo::localization::Pose pose
optional apollo::common::Point3D linear_velocity
Definition pose.proto:35
optional apollo::common::Quaternion orientation
Definition pose.proto:31
optional apollo::common::PointENU position
Definition pose.proto:26