1015 {
1016 cv::Mat image_2D = img.clone();
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035 if (show_vp_grid_) {
1036 cv::line(image_2D,
ground2image(camera_name, vp1_[camera_name]),
1038 }
1039
1040 if (show_lane_count_ > 0) {
1041 for (const auto &object : frame.lane_objects) {
1043 if (show_lane_count_ == 1) {
1044 cv::Point p_prev;
1045 p_prev.x = static_cast<int>(object.curve_image_point_set[0].x);
1046 p_prev.y = static_cast<int>(object.curve_image_point_set[0].y);
1047 Eigen::Vector2d p_prev_ground =
image2ground(camera_name, p_prev);
1048 for (unsigned i = 1; i < object.curve_image_point_set.size(); i++) {
1049 cv::Point p_cur;
1050 p_cur.x = static_cast<int>(object.curve_image_point_set[i].x);
1051 p_cur.y = static_cast<int>(object.curve_image_point_set[i].y);
1052 Eigen::Vector2d p_cur_ground =
image2ground(camera_name, p_cur);
1053
1054 if (p_cur.x >= 0 && p_cur.y >= 0 && p_prev.x >= 0 && p_prev.y >= 0 &&
1055 p_cur.x < image_width_ && p_cur.y < image_height_ &&
1056 p_prev.x < image_width_ && p_prev.y < image_height_) {
1057 cv::line(image_2D, p_prev, p_cur, lane_color, line_thickness_);
1058 }
1061 p_prev = p_cur;
1062 p_prev_ground = p_cur_ground;
1063 }
1064 } else if (show_lane_count_ == 2) {
1065 base::LaneLineCubicCurve curve_coord = object.curve_car_coord;
1066 Eigen::Vector2d p_prev_ground;
1067 float step =
1068 std::max(std::abs(curve_coord.x_end - curve_coord.x_start) /
1069 static_cast<float>(lane_step_num_),
1070 3.0f);
1071 float x = curve_coord.x_start;
1072 p_prev_ground(0) = x;
1073 p_prev_ground(1) = curve_coord.a * x * x * x + curve_coord.b * x * x +
1074 curve_coord.c * x + curve_coord.d;
1075 cv::Point p_prev =
ground2image(camera_name, p_prev_ground);
1076 x += step;
1077 for (unsigned int i = 0; x < curve_coord.x_end && i < lane_step_num_;
1078 x += step, i++) {
1079 Eigen::Vector2d p_cur_ground;
1080 p_cur_ground(0) = x;
1081 p_cur_ground(1) = curve_coord.a * x * x * x + curve_coord.b * x * x +
1082 curve_coord.c * x + curve_coord.d;
1083 cv::Point p_cur =
ground2image(camera_name, p_cur_ground);
1084 if (p_cur.x >= 0 && p_cur.y >= 0 && p_prev.x >= 0 && p_prev.y >= 0 &&
1085 p_cur.x < image_width_ && p_cur.y < image_height_ &&
1086 p_prev.x < image_width_ && p_prev.y < image_height_) {
1087 cv::line(image_2D, p_prev, p_cur, lane_color, line_thickness_);
1088 }
1091 p_prev = p_cur;
1092 p_prev_ground = p_cur_ground;
1093 }
1094 }
1095 }
1096 }
1097
1098
1099 for (const auto &object : frame.tracked_objects) {
1100
1102 cv::Rect r(static_cast<int>(rect.x), static_cast<int>(rect.y),
1103 static_cast<int>(rect.width), static_cast<int>(rect.height));
1105
1106 cv::putText(
1107 image_2D,
1108
1110 cv::Point(static_cast<int>(rect.x), static_cast<int>(rect.y) + 30),
1111 cv::FONT_HERSHEY_DUPLEX, 1,
red_color, 1);
1112
1113
1114 Eigen::Vector3d pos;
1115
1116 ADEBUG <<
"object->track_id: " <<
object->track_id;
1117
1118 double theta_ray;
1119 double theta;
1120 cv::Point c_2D;
1121 Eigen::Vector2d c_2D_l;
1122 if (show_homography_object_) {
1123 pos << object->camera_supplement.local_center(0),
1124 object->camera_supplement.local_center(1),
1125 object->camera_supplement.local_center(2);
1126 ADEBUG <<
"Camera pos: (" << pos(0) <<
", " << pos(1) <<
", " << pos(2)
1127 << ")";
1128 theta_ray = atan2(pos(0), pos(2));
1129 theta = object->camera_supplement.alpha + theta_ray;
1130
1131 c_2D.x = static_cast<int>(rect.x + rect.width / 2);
1132 c_2D.y = static_cast<int>(rect.y + rect.height);
1133 ADEBUG <<
"Image Footprint c_2D: (" << c_2D.x <<
", " << c_2D.y <<
")";
1135 ADEBUG <<
"Image Footprint position: (" << c_2D_l(0) <<
", " << c_2D_l(1)
1136 << ")";
1137 } else {
1138 pos = world2camera * object->center;
1139 theta_ray = atan2(pos(0), pos(2));
1140 theta = object->camera_supplement.alpha + theta_ray;
1141 ADEBUG <<
"Direct pos: (" << pos(0) <<
", " << pos(1) <<
", " << pos(2)
1142 << ")";
1143
1144
1145 c_2D_l(0) = pos(2);
1146 c_2D_l(1) = -pos(0);
1147 ADEBUG <<
"Direct center position: (" << c_2D_l(0) <<
", " << c_2D_l(1)
1148 << ")";
1149 }
1150 ADEBUG <<
"theta_ray: " << theta_ray * 180 / M_PI <<
" degree";
1151 ADEBUG <<
"object->camera_supplement.alpha: "
1152 << object->camera_supplement.alpha * 180 / M_PI << " degree";
1153 ADEBUG <<
"theta: " << theta * 180 / M_PI <<
" = "
1154 << object->camera_supplement.alpha * 180 / M_PI << " + "
1155 << theta_ray * 180 / M_PI;
1156
1157 float distance =
1158 static_cast<float>(sqrt(c_2D_l(0) * c_2D_l(0) + c_2D_l(1) * c_2D_l(1)));
1159 char dist_string[100];
1160 snprintf(dist_string, sizeof(dist_string), "%.1fm", distance);
1161
1162 cv::putText(
1163 image_2D, dist_string,
1164 cv::Point(static_cast<int>(rect.x), static_cast<int>(rect.y - 10)),
1166
1167 if (show_camera_box3d_) {
1168 Eigen::Matrix3d rotate_ry;
1169 rotate_ry <<
cos(theta), 0,
sin(theta), 0, 1, 0, -
sin(theta), 0,
1173 std::vector<cv::Point> p_proj(8);
1174 p[0] << object->size(0) * 0.5, object->size(2) * 0.5,
1175 object->size(1) * 0.5;
1176 p[1] << -object->size(0) * 0.5, object->size(2) * 0.5,
1177 object->size(1) * 0.5;
1178 p[2] << -object->size(0) * 0.5, object->size(2) * 0.5,
1179 -object->size(1) * 0.5;
1180 p[3] << object->size(0) * 0.5, object->size(2) * 0.5,
1181 -object->size(1) * 0.5;
1182 p[4] << object->size(0) * 0.5, -object->size(2) * 0.5,
1183 object->size(1) * 0.5;
1184 p[5] << -object->size(0) * 0.5, -object->size(2) * 0.5,
1185 object->size(1) * 0.5;
1186 p[6] << -object->size(0) * 0.5, -object->size(2) * 0.5,
1187 -object->size(1) * 0.5;
1188 p[7] << object->size(0) * 0.5, -object->size(2) * 0.5,
1189 -object->size(1) * 0.5;
1190
1191 for (uint i = 0; i < p.size(); i++) {
1192 proj[i] = intrinsic * (rotate_ry * p[i] + pos);
1193 if (fabs(p[i](2)) > std::numeric_limits<double>::min()) {
1194 p_proj[i].x = static_cast<int>(proj[i](0) / proj[i](2));
1195 p_proj[i].y = static_cast<int>(proj[i](1) / proj[i](2));
1196 }
1197 }
1198 if (object->b_cipv) {
1199 cv::line(image_2D, p_proj[0], p_proj[1], color_cipv_,
1200 cipv_line_thickness_);
1201 cv::line(image_2D, p_proj[1], p_proj[2], color_cipv_,
1202 cipv_line_thickness_);
1203 cv::line(image_2D, p_proj[2], p_proj[3], color_cipv_,
1204 cipv_line_thickness_);
1205 cv::line(image_2D, p_proj[3], p_proj[0], color_cipv_,
1206 cipv_line_thickness_);
1207 cv::line(image_2D, p_proj[4], p_proj[5], color_cipv_,
1208 cipv_line_thickness_);
1209 cv::line(image_2D, p_proj[5], p_proj[6], color_cipv_,
1210 cipv_line_thickness_);
1211 cv::line(image_2D, p_proj[6], p_proj[7], color_cipv_,
1212 cipv_line_thickness_);
1213 cv::line(image_2D, p_proj[7], p_proj[4], color_cipv_,
1214 cipv_line_thickness_);
1215 cv::line(image_2D, p_proj[0], p_proj[4], color_cipv_,
1216 cipv_line_thickness_);
1217 cv::line(image_2D, p_proj[1], p_proj[5], color_cipv_,
1218 cipv_line_thickness_);
1219 cv::line(image_2D, p_proj[2], p_proj[6], color_cipv_,
1220 cipv_line_thickness_);
1221 cv::line(image_2D, p_proj[3], p_proj[7], color_cipv_,
1222 cipv_line_thickness_);
1223 }
1224
1225 cv::line(image_2D, p_proj[0], p_proj[1], color, line_thickness_);
1226 cv::line(image_2D, p_proj[1], p_proj[2], color, line_thickness_);
1227 cv::line(image_2D, p_proj[2], p_proj[3], color, line_thickness_);
1228 cv::line(image_2D, p_proj[3], p_proj[0], color, line_thickness_);
1229 cv::line(image_2D, p_proj[4], p_proj[5], color, line_thickness_);
1230 cv::line(image_2D, p_proj[5], p_proj[6], color, line_thickness_);
1231 cv::line(image_2D, p_proj[6], p_proj[7], color, line_thickness_);
1232 cv::line(image_2D, p_proj[7], p_proj[4], color, line_thickness_);
1233 cv::line(image_2D, p_proj[0], p_proj[4], color, line_thickness_);
1234 cv::line(image_2D, p_proj[1], p_proj[5], color, line_thickness_);
1235 cv::line(image_2D, p_proj[2], p_proj[6], color, line_thickness_);
1236 cv::line(image_2D, p_proj[3], p_proj[7], color, line_thickness_);
1237 } else {
1238 if (object->b_cipv) {
1239 cv::rectangle(image_2D, r, color_cipv_, cipv_line_thickness_);
1240 }
1241 cv::rectangle(image_2D, r, color, 2);
1242 }
1243
1244
1245 Eigen::Matrix2d rotate_rz;
1246 theta = theta - M_PI_2;
1247 rotate_rz <<
cos(theta),
sin(theta), -
sin(theta),
cos(theta);
1248 Eigen::Vector2d p1;
1249 p1 << object->size(0) * 0.5, object->size(1) * 0.5;
1250 p1 = rotate_rz * p1 + c_2D_l;
1251 Eigen::Vector2d p2;
1252 p2 << -object->size(0) * 0.5, object->size(1) * 0.5;
1253 p2 = rotate_rz * p2 + c_2D_l;
1254 Eigen::Vector2d p3;
1255 p3 << -object->size(0) * 0.5, -object->size(1) * 0.5;
1256 p3 = rotate_rz * p3 + c_2D_l;
1257 Eigen::Vector2d p4;
1258 p4 << object->size(0) * 0.5, -object->size(1) * 0.5;
1259 p4 = rotate_rz * p4 + c_2D_l;
1260
1261 Eigen::Vector2d pos_2d;
1262 pos_2d << c_2D_l(0), c_2D_l(1);
1263 Eigen::Vector3d v;
1264 v << object->velocity(0), object->velocity(1), object->velocity(2);
1265 v = world2camera.linear() * v;
1266 Eigen::Vector2d v_2d;
1267 v_2d << v(0) + pos_2d(0), v(1) + pos_2d(1);
1268
1269 AINFO <<
"v.norm: " << v.norm();
1270 if (show_trajectory_ && motion_buffer != nullptr &&
1271 motion_buffer->size() > 0 && v.norm() > speed_limit_) {
1273 }
1274 if (object->b_cipv) {
1283
1284
1285
1286 }
1288 color, line_thickness_);
1290 color, line_thickness_);
1292 color, line_thickness_);
1294 color, line_thickness_);
1295
1296
1297 }
1298
1299
1300 if (show_virtual_egolane_) {
1301 EgoLane virtual_egolane_ground;
1302 virtual_egolane_ground.left_line.line_point.clear();
1303 virtual_egolane_ground.right_line.line_point.clear();
1304 CipvOptions cipv_options;
1305 if (motion_buffer == nullptr || motion_buffer->size() == 0) {
1306 AWARN <<
"motion_buffer_ is empty";
1307 cipv_options.velocity = 5.0f;
1308 cipv_options.yaw_rate = 0.0f;
1309 } else {
1310 cipv_options.velocity = motion_buffer->back().velocity;
1311 cipv_options.yaw_rate = motion_buffer->back().yaw_rate;
1312 }
1314 cipv_options.yaw_rate, cipv_options.velocity,
1316 &virtual_egolane_ground.right_line);
1317
1318 Eigen::Vector2d p_prev_ground;
1319 p_prev_ground(0) = virtual_egolane_ground.left_line.line_point[0](0);
1320 p_prev_ground(1) = virtual_egolane_ground.left_line.line_point[0](1);
1321 cv::Point p_prev =
ground2image(camera_name, p_prev_ground);
1322 for (unsigned i = 1; i < virtual_egolane_ground.left_line.line_point.size();
1323 i++) {
1324 Eigen::Vector2d p_cur_ground;
1325 p_cur_ground(0) = virtual_egolane_ground.left_line.line_point[i](0);
1326 p_cur_ground(1) = virtual_egolane_ground.left_line.line_point[i](1);
1327 cv::Point p_cur =
ground2image(camera_name, p_cur_ground);
1328 if (p_cur.x >= 0 && p_cur.y >= 0 && p_prev.x >= 0 && p_prev.y >= 0 &&
1329 p_cur.x < image_width_ && p_cur.y < image_height_ &&
1330 p_prev.x < image_width_ && p_prev.y < image_height_) {
1331 cv::line(image_2D, p_prev, p_cur, virtual_lane_color_, line_thickness_);
1332 }
1335 p_prev = p_cur;
1336 p_prev_ground = p_cur_ground;
1337 }
1338
1339
1340 p_prev_ground(0) = virtual_egolane_ground.right_line.line_point[0](0);
1341 p_prev_ground(1) = virtual_egolane_ground.right_line.line_point[0](1);
1343 for (unsigned i = 1;
1344 i < virtual_egolane_ground.right_line.line_point.size(); i++) {
1345 Eigen::Vector2d p_cur_ground;
1346 p_cur_ground(0) = virtual_egolane_ground.right_line.line_point[i](0);
1347 p_cur_ground(1) = virtual_egolane_ground.right_line.line_point[i](1);
1348 cv::Point p_cur =
ground2image(camera_name, p_cur_ground);
1349
1350 if (p_cur.x >= 0 && p_cur.y >= 0 && p_prev.x >= 0 && p_prev.y >= 0 &&
1351 p_cur.x < image_width_ && p_cur.y < image_height_ &&
1352 p_prev.x < image_width_ && p_prev.y < image_height_) {
1353 cv::line(image_2D, p_prev, p_cur, virtual_lane_color_, line_thickness_);
1354 }
1357 p_prev = p_cur;
1358 p_prev_ground = p_cur_ground;
1359 }
1360 }
1361
1362 last_timestamp_ = frame.timestamp;
1363 camera_image_[frame.data_provider->sensor_name()] = image_2D;
1364 cv::resize(image_2D, camera_image_[frame.data_provider->sensor_name()],
1365 cv::Size(small_w_, small_h_));
1366}
static bool MakeVirtualEgoLaneFromYawRate(const float yaw_rate, const float velocity, const float offset_distance, LaneLineSimple *left_lane_line, LaneLineSimple *right_lane_line)
bool DrawTrajectories(const base::ObjectPtr &object, const base::MotionBufferPtr motion_buffer)
std::string sub_type_to_string(const apollo::perception::base::ObjectSubType type)
cv::Point ground2image(const std::string &camera_name, const Eigen::Vector2d &p_ground)
Eigen::Vector2d image2ground(const std::string &camera_name, cv::Point p_img)
std::vector< EigenType, Eigen::aligned_allocator< EigenType > > EigenVector
std::map< base::LaneLinePositionType, cv::Scalar > colormapline
constexpr float kMaxVehicleWidthInMeter