Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
55f291ef
A
apollo
项目概览
Pinoxchio
/
apollo
与 Fork 源项目一致
从无法访问的项目Fork
通知
2
Star
0
Fork
0
代码
文件
提交
分支
Tags
贡献者
分支图
Diff
Issue
0
列表
看板
标记
里程碑
合并请求
0
Wiki
0
Wiki
分析
仓库
DevOps
项目成员
Pages
A
apollo
项目概览
项目概览
详情
发布
仓库
仓库
文件
提交
分支
标签
贡献者
分支图
比较
Issue
0
Issue
0
列表
看板
标记
里程碑
合并请求
0
合并请求
0
Pages
分析
分析
仓库分析
DevOps
Wiki
0
Wiki
成员
成员
收起侧边栏
关闭侧边栏
动态
分支图
创建新Issue
提交
Issue看板
体验新版 GitCode,发现更多精彩内容 >>
提交
55f291ef
编写于
6月 28, 2019
作者:
T
Tae Eun Choe
提交者:
Yuliang Guo
6月 28, 2019
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Perception: Make visualizer full screen; Changed parameter of CIPO (#9051)
Percpetion: typo
上级
71c74f08
变更
4
隐藏空白更改
内联
并排
Showing
4 changed file
with
28 addition
and
12 deletion
+28
-12
modules/perception/camera/app/cipv_camera.cc
modules/perception/camera/app/cipv_camera.cc
+11
-7
modules/perception/camera/app/cipv_camera.h
modules/perception/camera/app/cipv_camera.h
+8
-2
modules/perception/camera/common/lane_object.h
modules/perception/camera/common/lane_object.h
+1
-1
modules/perception/camera/tools/offline/visualizer.cc
modules/perception/camera/tools/offline/visualizer.cc
+8
-2
未找到文件。
modules/perception/camera/app/cipv_camera.cc
浏览文件 @
55f291ef
...
...
@@ -208,7 +208,7 @@ bool Cipv::ElongateEgoLane(const std::vector<base::LaneLine> &lane_objects,
const
bool
b_left_valid
,
const
bool
b_right_valid
,
const
float
yaw_rate
,
const
float
velocity
,
EgoLane
*
egolane_image
,
EgoLane
*
egolane_ground
)
{
float
offset_distance
=
half_v
irtual_egolan
e_width_in_meter_
;
float
offset_distance
=
half_v
ehicl
e_width_in_meter_
;
// When left lane line is available
if
(
b_left_valid
&&
b_right_valid
)
{
// elongate both lanes or do nothing
...
...
@@ -676,13 +676,16 @@ bool Cipv::IsObjectInTheLaneImage(const std::shared_ptr<base::Object> &object,
bool
Cipv
::
IsObjectInTheLaneGround
(
const
std
::
shared_ptr
<
base
::
Object
>
&
object
,
const
EgoLane
&
egolane_ground
,
const
Eigen
::
Affine3d
world2camera
,
const
bool
b_virtual
,
float
*
object_distance
)
{
LineSegment2Df
closted_object_edge
;
bool
b_left_lane_clear
=
false
;
bool
b_right_lane_clear
=
false
;
float
shortest_distance
=
0.0
f
;
float
distance
=
0.0
f
;
float
max_dist_object_to_lane_in_meter
=
b_virtual
?
max_dist_object_to_virtual_lane_in_meter_
:
max_dist_object_to_lane_in_meter_
;
int
closest_index
=
-
1
;
// Find closest edge of a given object bounding box
float
b_valid_object
=
FindClosestObjectGround
(
...
...
@@ -734,7 +737,7 @@ bool Cipv::IsObjectInTheLaneGround(const std::shared_ptr<base::Object> &object,
closted_object_edge
.
end_point
,
egolane_ground
.
left_line
.
line_point
[
closest_index
],
egolane_ground
.
left_line
.
line_point
[
closest_index
+
1
])
&&
shortest_distance
<
max_dist_object_to_lane_in_meter
_
)
{
shortest_distance
<
max_dist_object_to_lane_in_meter
)
{
b_left_lane_clear
=
true
;
}
}
...
...
@@ -776,7 +779,7 @@ bool Cipv::IsObjectInTheLaneGround(const std::shared_ptr<base::Object> &object,
closted_object_edge
.
start_point
,
egolane_ground
.
right_line
.
line_point
[
closest_index
],
egolane_ground
.
right_line
.
line_point
[
closest_index
+
1
])
&&
shortest_distance
<
max_dist_object_to_lane_in_meter
_
)
{
shortest_distance
<
max_dist_object_to_lane_in_meter
)
{
b_right_lane_clear
=
true
;
}
}
...
...
@@ -789,12 +792,13 @@ bool Cipv::IsObjectInTheLane(const std::shared_ptr<base::Object> &object,
const
EgoLane
&
egolane_image
,
const
EgoLane
&
egolane_ground
,
const
Eigen
::
Affine3d
world2camera
,
const
bool
b_virtual
,
float
*
distance
)
{
if
(
b_image_based_cipv_
)
{
return
IsObjectInTheLaneImage
(
object
,
egolane_image
,
distance
);
}
return
IsObjectInTheLaneGround
(
object
,
egolane_ground
,
world2camera
,
distance
);
b_virtual
,
distance
);
}
// =====================================================================
...
...
@@ -840,9 +844,9 @@ bool Cipv::DetermineCipv(const std::vector<base::LaneLine> &lane_objects,
AINFO
<<
"objects["
<<
i
<<
"]->track_id: "
<<
(
*
objects
)[
i
]
->
track_id
;
}
if
(
IsObjectInTheLane
((
*
objects
)[
i
],
egolane_image
,
egolane_ground
,
world2camera
,
&
distance
)
||
world2camera
,
false
,
&
distance
)
||
IsObjectInTheLane
((
*
objects
)[
i
],
egolane_image
,
virtual_egolane_ground
,
world2camera
,
&
distance
))
{
world2camera
,
true
,
&
distance
))
{
if
(
cipv_index
<
0
||
distance
<
min_distance
)
{
cipv_index
=
i
;
cipv_track_id
=
(
*
objects
)[
i
]
->
track_id
;
...
...
modules/perception/camera/app/cipv_camera.h
浏览文件 @
55f291ef
...
...
@@ -41,8 +41,9 @@ struct CipvOptions {
float
yaw_angle
=
0.0
f
;
};
constexpr
float
kMinVelocity
=
1
5
.0
f
;
// in m/s
constexpr
float
kMinVelocity
=
1
0
.0
f
;
// in m/s
constexpr
float
kMaxDistObjectToLaneInMeter
=
70.0
f
;
constexpr
float
kMaxDistObjectToVirtualLaneInMeter
=
10.0
f
;
constexpr
float
kMaxDistObjectToLaneInPixel
=
10.0
f
;
const
std
::
size_t
kDropsHistorySize
=
20
;
const
std
::
size_t
kMaxObjectNum
=
100
;
...
...
@@ -141,13 +142,16 @@ class Cipv {
bool
IsObjectInTheLaneGround
(
const
std
::
shared_ptr
<
base
::
Object
>
&
object
,
const
EgoLane
&
egolane_ground
,
const
Eigen
::
Affine3d
world2camera
,
const
bool
b_virtual
,
float
*
distance
);
// Check if the object is in the lane in ego-ground space
bool
IsObjectInTheLane
(
const
std
::
shared_ptr
<
base
::
Object
>
&
object
,
const
EgoLane
&
egolane_image
,
const
EgoLane
&
egolane_ground
,
const
Eigen
::
Affine3d
world2camera
,
float
*
distance
);
const
Eigen
::
Affine3d
world2camera
,
const
bool
b_virtual
,
float
*
distance
);
// Check if a point is left of a line segment
bool
IsPointLeftOfLine
(
const
Point2Df
&
point
,
...
...
@@ -186,6 +190,8 @@ class Cipv {
single_virtual_egolane_width_in_meter_
*
0.5
f
;
float
half_vehicle_width_in_meter_
=
kMaxVehicleWidthInMeter
*
0.5
f
;
float
max_dist_object_to_lane_in_meter_
=
kMaxDistObjectToLaneInMeter
;
float
max_dist_object_to_virtual_lane_in_meter_
=
kMaxDistObjectToVirtualLaneInMeter
;
float
max_dist_object_to_lane_in_pixel_
=
kMaxDistObjectToLaneInPixel
;
float
MAX_VEHICLE_WIDTH_METER
=
5.0
f
;
float
EPSILON
=
1.0e-6
f
;
...
...
modules/perception/camera/common/lane_object.h
浏览文件 @
55f291ef
...
...
@@ -36,7 +36,7 @@ constexpr uint32_t kMinLaneLineLengthForCIPV = 2;
// Average width of lane
constexpr
float
kAverageLaneWidthInMeter
=
3.7
f
;
// Maximum vehicle width
constexpr
float
kMaxVehicleWidthInMeter
=
2.5
f
;
constexpr
float
kMaxVehicleWidthInMeter
=
1.87
f
;
// Margin from a virtual car lane to actual lane
constexpr
float
kMarginVehicleToLane
=
(
kAverageLaneWidthInMeter
-
kMaxVehicleWidthInMeter
)
/
2.0
f
;
...
...
modules/perception/camera/tools/offline/visualizer.cc
浏览文件 @
55f291ef
...
...
@@ -919,7 +919,10 @@ void Visualizer::ShowResult(const cv::Mat &img, const CameraFrame &frame) {
}
if
(
cv_imshow_img_
)
{
cv
::
imshow
(
""
,
bigimg
);
cv
::
namedWindow
(
"Apollo Visualizer"
,
CV_WINDOW_NORMAL
);
cv
::
setWindowProperty
(
"Apollo Visualizer"
,
CV_WND_PROP_FULLSCREEN
,
CV_WINDOW_FULLSCREEN
);
cv
::
imshow
(
"Apollo Visualizer"
,
bigimg
);
int
key
=
cvWaitKey
(
30
);
key_handler
(
camera_name
,
key
);
}
...
...
@@ -1364,7 +1367,10 @@ void Visualizer::ShowResult_all_info_single_camera(const cv::Mat &img,
}
if
(
cv_imshow_img_
)
{
cv
::
imshow
(
""
,
bigimg
);
cv
::
namedWindow
(
"Apollo Visualizer"
,
CV_WINDOW_NORMAL
);
cv
::
setWindowProperty
(
"Apollo Visualizer"
,
CV_WND_PROP_FULLSCREEN
,
CV_WINDOW_FULLSCREEN
);
cv
::
imshow
(
"Apollo Visualizer"
,
bigimg
);
int
key
=
cvWaitKey
(
30
);
key_handler
(
camera_name
,
key
);
}
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录