Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
e3f82ba2
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,发现更多精彩内容 >>
提交
e3f82ba2
编写于
9月 01, 2017
作者:
S
siyangy
提交者:
Aaron Xiao
9月 01, 2017
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Remove std::cout
上级
7880c902
变更
10
隐藏空白更改
内联
并排
Showing
10 changed file
with
32 addition
and
37 deletion
+32
-37
modules/calibration/lidar_ex_checker/lidar_ex_checker.cc
modules/calibration/lidar_ex_checker/lidar_ex_checker.cc
+0
-4
modules/calibration/republish_msg/republish_msg.cc
modules/calibration/republish_msg/republish_msg.cc
+0
-2
modules/canbus/can_client/can_client_tool.cc
modules/canbus/can_client/can_client_tool.cc
+27
-14
modules/canbus/vehicle/lincoln/protocol/gps_6d_test.cc
modules/canbus/vehicle/lincoln/protocol/gps_6d_test.cc
+0
-2
modules/common/time/time.h
modules/common/time/time.h
+2
-2
modules/perception/obstacle/common/hungarian_bigraph_matcher.cc
...s/perception/obstacle/common/hungarian_bigraph_matcher.cc
+0
-1
modules/perception/obstacle/lidar/object_builder/min_box/min_box.cc
...rception/obstacle/lidar/object_builder/min_box/min_box.cc
+0
-2
modules/perception/obstacle/lidar/roi_filter/hdmap_roi_filter/hdmap_roi_filter_test.cc
...idar/roi_filter/hdmap_roi_filter/hdmap_roi_filter_test.cc
+0
-1
modules/perception/obstacle/lidar/tracker/hm_tracker/object_track.cc
...ception/obstacle/lidar/tracker/hm_tracker/object_track.cc
+3
-5
modules/planning/math/smoothing_spline/spline_1d_kernel_test.cc
...s/planning/math/smoothing_spline/spline_1d_kernel_test.cc
+0
-4
未找到文件。
modules/calibration/lidar_ex_checker/lidar_ex_checker.cc
浏览文件 @
e3f82ba2
...
...
@@ -79,9 +79,6 @@ bool LidarExChecker::GetExtrinsics() {
tf2_buffer
.
lookupTransform
(
"novatel"
,
"velodyne64"
,
ros
::
Time
(
0
));
tf
::
transformMsgToEigen
(
transform_stamped
.
transform
,
extrinsics_
);
std
::
cout
<<
"velodyne64 extrinsics: "
<<
std
::
endl
;
std
::
cout
<<
extrinsics_
.
matrix
()
<<
std
::
endl
;
return
true
;
}
...
...
@@ -164,7 +161,6 @@ void LidarExChecker::OnPointCloud(const sensor_msgs::PointCloud2& message) {
if
(
clouds_
.
size
()
<
cloud_count_
)
{
last_position_
=
position
;
clouds_
.
push_back
(
cld
);
std
::
cout
<<
"take "
<<
clouds_
.
size
()
<<
" cloud(s)."
<<
std
::
endl
;
}
if
(
clouds_
.
size
()
>=
cloud_count_
)
{
...
...
modules/calibration/republish_msg/republish_msg.cc
浏览文件 @
e3f82ba2
...
...
@@ -32,8 +32,6 @@ std::string RepublishMsg::Name() const {
}
Status
RepublishMsg
::
Init
()
{
std
::
cout
<<
FLAGS_adapter_config_path
<<
std
::
endl
;
AdapterManager
::
Init
(
FLAGS_adapter_config_path
);
CHECK
(
AdapterManager
::
GetInsStat
())
<<
"INS status is not initialized."
;
...
...
modules/canbus/can_client/can_client_tool.cc
浏览文件 @
e3f82ba2
...
...
@@ -60,13 +60,12 @@ struct TestCanParam {
TestCanParam
()
=
default
;
void
print
()
{
std
::
cout
<<
"conf: "
<<
conf
.
ShortDebugString
()
<<
", total send: "
<<
send_cnt
+
send_err_cnt
<<
"/"
<<
FLAGS_agent_mutual_send_frames
<<
", send_ok: "
<<
send_cnt
<<
" , send_err_cnt: "
<<
send_err_cnt
<<
", send_lost_cnt: "
<<
send_lost_cnt
<<
", recv_cnt: "
<<
recv_cnt
<<
", send_time: "
<<
send_time
<<
", recv_time: "
<<
recv_time
<<
std
::
endl
;
AINFO
<<
"conf: "
<<
conf
.
ShortDebugString
()
<<
", total send: "
<<
send_cnt
+
send_err_cnt
<<
"/"
<<
FLAGS_agent_mutual_send_frames
<<
", send_ok: "
<<
send_cnt
<<
" , send_err_cnt: "
<<
send_err_cnt
<<
", send_lost_cnt: "
<<
send_lost_cnt
<<
", recv_cnt: "
<<
recv_cnt
<<
", send_time: "
<<
send_time
<<
", recv_time: "
<<
recv_time
;
}
};
...
...
@@ -74,9 +73,13 @@ class CanAgent {
public:
explicit
CanAgent
(
TestCanParam
*
param_ptr
)
:
param_ptr_
(
param_ptr
)
{}
TestCanParam
*
param_ptr
()
{
return
param_ptr_
;
}
TestCanParam
*
param_ptr
()
{
return
param_ptr_
;
}
CanAgent
*
other_agent
()
{
return
other_agent_
;
}
CanAgent
*
other_agent
()
{
return
other_agent_
;
}
bool
Start
()
{
thread_recv_
.
reset
(
new
std
::
thread
([
this
]
{
RecvThreadFunc
();
}));
...
...
@@ -167,15 +170,25 @@ class CanAgent {
return
;
}
void
AddOtherAgent
(
CanAgent
*
agent
)
{
other_agent_
=
agent
;
}
void
AddOtherAgent
(
CanAgent
*
agent
)
{
other_agent_
=
agent
;
}
bool
is_receiving
()
{
return
is_receiving_
;
}
bool
is_receiving
()
{
return
is_receiving_
;
}
void
is_receiving
(
bool
val
)
{
is_receiving_
=
val
;
}
void
is_receiving
(
bool
val
)
{
is_receiving_
=
val
;
}
bool
is_sending_finish
()
{
return
is_sending_finish_
;
}
bool
is_sending_finish
()
{
return
is_sending_finish_
;
}
void
is_sending_finish
(
bool
val
)
{
is_sending_finish_
=
val
;
}
void
is_sending_finish
(
bool
val
)
{
is_sending_finish_
=
val
;
}
void
RecvThreadFunc
()
{
using
::
apollo
::
common
::
time
::
Clock
;
...
...
modules/canbus/vehicle/lincoln/protocol/gps_6d_test.cc
浏览文件 @
e3f82ba2
...
...
@@ -33,8 +33,6 @@ TEST(Gps6dTest, General) {
EXPECT_DOUBLE_EQ
(
cd
.
basic
().
latitude
(),
-
244.245646
);
EXPECT_DOUBLE_EQ
(
cd
.
basic
().
longitude
(),
-
61.779717
);
std
::
cout
<<
cd
.
DebugString
()
<<
std
::
endl
;
EXPECT_EQ
(
data
[
0
],
0b01010110
);
EXPECT_EQ
(
data
[
1
],
0b01010010
);
EXPECT_EQ
(
data
[
2
],
0b01010011
);
...
...
modules/common/time/time.h
浏览文件 @
e3f82ba2
...
...
@@ -268,8 +268,8 @@ inline Clock::Clock()
[block_start_time]() { \
double now = Clock::NowInSecond(); \
if (now - block_start_time > (threshold)) { \
std::cout << std::fixed << (message) << ": "
\
<< now - block_start_time << std::endl;
\
ADEBUG << std::fixed << (message) << ": "
\
<< now - block_start_time;
\
} \
}())
...
...
modules/perception/obstacle/common/hungarian_bigraph_matcher.cc
浏览文件 @
e3f82ba2
...
...
@@ -276,7 +276,6 @@ void HungarianOptimizer::do_munkres() {
(
this
->*
_state
)();
++
iter_num
;
}
// std::cout << "do_munkres iterations: " << iter_num << std::endl;
if
(
iter_num
>=
max_iter
)
{
check_star
();
}
...
...
modules/perception/obstacle/lidar/object_builder/min_box/min_box.cc
浏览文件 @
e3f82ba2
...
...
@@ -204,10 +204,8 @@ void MinBoxObjectBuilder::ReconstructPolygon(
p_j
[
2
]
=
obj
->
polygon
.
points
[
j
].
z
;
Eigen
::
Vector3d
ray
=
p
-
min_point
;
if
(
line
[
0
]
*
ray
[
1
]
-
ray
[
0
]
*
line
[
1
]
<
0
)
{
// std::cout << "in :" << std::endl;
}
else
{
// outline
// std::cout << "out :" << std::endl;
has_out
=
true
;
}
}
else
if
(
j
==
min_point_index
||
j
==
max_point_index
)
{
...
...
modules/perception/obstacle/lidar/roi_filter/hdmap_roi_filter/hdmap_roi_filter_test.cc
浏览文件 @
e3f82ba2
...
...
@@ -133,7 +133,6 @@ void HdmapROIFilterTest::filter() {
TEST_F
(
HdmapROIFilterTest
,
test_filter
)
{
init
();
std
::
cout
<<
"Successfully init."
<<
std
::
endl
;
filter
();
}
...
...
modules/perception/obstacle/lidar/tracker/hm_tracker/object_track.cc
浏览文件 @
e3f82ba2
...
...
@@ -125,7 +125,7 @@ void ObjectTrack::UpdateWithObject(TrackedObjectPtr* new_object,
filter_
->
UpdateWithObject
((
*
new_object
),
current_object_
,
time_diff
);
filter_
->
GetState
(
&
belief_anchor_point_
,
&
belief_velocity_
);
}
else
{
/* Here, we only update belief anchor point with anchor point of new detected object. In
/* Here, we only update belief anchor point with anchor point of new detected object. In
* the future, new method that handle outlier could be designed to handle more complicated
* strategies. */
belief_anchor_point_
=
(
*
new_object
)
->
anchor_point
;
...
...
@@ -140,7 +140,7 @@ void ObjectTrack::UpdateWithObject(TrackedObjectPtr* new_object,
belief_velocity_accelaration_
=
((
*
new_object
)
->
velocity
-
current_object_
->
velocity
)
/
time_diff
;
/* Currently, we only considered outliers' influence on motion estimation. Track level
/* Currently, we only considered outliers' influence on motion estimation. Track level
* smoothness of orientation & class idx may also take into acount it in the future. */
// 1.4 update track info
...
...
@@ -161,7 +161,7 @@ void ObjectTrack::UpdateWithObject(TrackedObjectPtr* new_object,
* is more reasonable to be used in the smoothing of orientation & type. */
/* Previously, track static hypothesis is checked before smoothing strategies. Now, it has been
* moved in the method of smooth track velocity. This is more reasonable, as track static
* moved in the method of smooth track velocity. This is more reasonable, as track static
* hypothesis is decided by velocity more directly when velocity estimation improved. */
/* 2. smooth object track */
...
...
@@ -396,9 +396,7 @@ ObjectTrackSet::ObjectTrackSet(): age_threshold_(5),
}
ObjectTrackSet
::~
ObjectTrackSet
()
{
std
::
cout
<<
"Release ObjectTrackSet...
\n
"
;
clear
();
std
::
cout
<<
"Release ObjectTrackSet End
\n
"
;
}
void
ObjectTrackSet
::
clear
()
{
...
...
modules/planning/math/smoothing_spline/spline_1d_kernel_test.cc
浏览文件 @
e3f82ba2
...
...
@@ -31,15 +31,11 @@ TEST(Spline1dKernel, add_reference_line_kernel) {
Spline1dKernel
kernel
(
x_knots
,
spline_order
);
Eigen
::
IOFormat
OctaveFmt
(
Eigen
::
StreamPrecision
,
0
,
", "
,
";
\n
"
,
""
,
""
,
"["
,
"]"
);
std
::
cout
<<
kernel
.
kernel_matrix
().
format
(
OctaveFmt
)
<<
std
::
endl
;
std
::
vector
<
double
>
x_coord
=
{
0.0
,
1.0
,
2.0
,
3.0
};
std
::
vector
<
double
>
ref_x
=
{
0.0
,
0.5
,
0.6
,
2.0
};
kernel
.
add_reference_line_kernel_matrix
(
x_coord
,
ref_x
,
1.0
);
std
::
cout
<<
kernel
.
kernel_matrix
().
format
(
OctaveFmt
)
<<
std
::
endl
;
std
::
cout
<<
kernel
.
offset
().
format
(
OctaveFmt
)
<<
std
::
endl
;
Eigen
::
MatrixXd
ref_kernel_matrix
=
Eigen
::
MatrixXd
::
Zero
(
15
,
15
);
ref_kernel_matrix
<<
1
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录