Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
b98c0016
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,发现更多精彩内容 >>
提交
b98c0016
编写于
8月 15, 2017
作者:
A
Aaron Xiao
提交者:
Jiangtao Hu
8月 15, 2017
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Tools: Add common module for python tools.
上级
98f8bd05
变更
10
隐藏空白更改
内联
并排
Showing
10 changed file
with
86 addition
and
85 deletion
+86
-85
modules/tools/calibration/result2pb.py
modules/tools/calibration/result2pb.py
+3
-12
modules/tools/common/__init__.py
modules/tools/common/__init__.py
+0
-0
modules/tools/common/proto_utils.py
modules/tools/common/proto_utils.py
+46
-0
modules/tools/mapshow/README.md
modules/tools/mapshow/README.md
+14
-10
modules/tools/mapshow/localization.py
modules/tools/mapshow/localization.py
+4
-7
modules/tools/mapshow/map.py
modules/tools/mapshow/map.py
+3
-15
modules/tools/perception/extend_prediction.py
modules/tools/perception/extend_prediction.py
+3
-15
modules/tools/planning_traj_plot/main.py
modules/tools/planning_traj_plot/main.py
+7
-23
modules/tools/planning_traj_plot/run.sh
modules/tools/planning_traj_plot/run.sh
+1
-1
scripts/apollo_base.sh
scripts/apollo_base.sh
+5
-2
未找到文件。
modules/tools/calibration/result2pb.py
浏览文件 @
b98c0016
...
...
@@ -18,12 +18,11 @@
import
sys
from
google.protobuf
import
text_format
import
numpy
as
np
sys
.
path
.
append
(
"../../bazel-genfiles"
)
import
common.proto_utils
as
proto_utils
from
modules.control.proto
import
calibration_table_pb2
from
modules.control.proto
import
control_conf_pb2
from
modules.control.proto
.control_conf_pb2
import
ControlConf
def
load_calibration_raw_data
(
fn
):
...
...
@@ -85,14 +84,6 @@ def load_calibration_raw_data_old(fn):
return
speed_table
def
load_old_control_conf_pb_txt
(
control_conf_pb_txt_file
):
control_conf_pb
=
control_conf_pb2
.
ControlConf
()
f_handle
=
open
(
control_conf_pb_txt_file
,
'r'
)
text_format
.
Merge
(
f_handle
.
read
(),
control_conf_pb
)
f_handle
.
close
()
return
control_conf_pb
def
get_calibration_table_pb
(
speed_table
):
calibration_table_pb
=
calibration_table_pb2
.
ControlCalibrationTable
()
speeds
=
speed_table
.
keys
()
...
...
@@ -115,7 +106,7 @@ if __name__ == "__main__":
if
len
(
sys
.
argv
)
<
2
:
print
"usage: python plot_results.py old_control_conf.pb.txt result.csv"
ctl_conf_pb
=
load_old_control_conf_pb_txt
(
sys
.
argv
[
1
]
)
ctl_conf_pb
=
proto_utils
.
get_pb_from_text_file
(
sys
.
argv
[
1
],
ControlConf
()
)
speed_table_dict
=
load_calibration_raw_data
(
sys
.
argv
[
2
])
calibration_table_pb
=
get_calibration_table_pb
(
speed_table_dict
)
ctl_conf_pb
.
lon_controller_conf
.
calibration_table
.
CopyFrom
(
...
...
modules/tools/common/__init__.py
0 → 100644
浏览文件 @
b98c0016
modules/tools/
mapshow/setup.sh
→
modules/tools/
common/proto_utils.py
100755 → 100644
浏览文件 @
b98c0016
#!/usr/bin/env
bash
#!/usr/bin/env
python
###############################################################################
# Copyright 2017 The Apollo Authors. All Rights Reserved.
...
...
@@ -15,7 +15,32 @@
# See the License for the specific language governing permissions and
# limitations under the License.
###############################################################################
"""Protobuf utils."""
import
google.protobuf.text_format
as
text_format
DIR
=
"
$(
cd
"
$(
dirname
"
${
BASH_SOURCE
[0]
}
"
)
"
&&
pwd
)
"
export
PYTHONPATH
=
"
${
DIR
}
/../../../bazel-genfiles:
${
PYTHONPATH
}
"
def
get_pb_from_text_file
(
filename
,
proto_obj
):
"""Get a proto from given text file."""
with
open
(
filename
,
'r'
)
as
file_in
:
return
text_format
.
Merge
(
file_in
.
read
(),
proto_obj
)
def
get_pb_from_bin_file
(
filename
,
proto_obj
):
"""Get a proto from given binary file."""
with
open
(
filename
,
'rb'
)
as
file_in
:
proto_obj
.
ParseFromString
(
file_in
.
read
())
return
proto_obj
def
get_pb_from_file
(
filename
,
proto_obj
):
"""Get a proto from given file by trying binary mode and text mode."""
try
:
return
get_pb_from_bin_file
(
filename
,
proto_obj
)
except
:
print
'Info: Cannot parse %s as binary proto.'
%
filename
try
:
return
get_pb_from_text_file
(
filename
,
proto_obj
)
except
:
print
'Error: Cannot parse %s as text proto'
%
filename
return
None
modules/tools/mapshow/README.md
浏览文件 @
b98c0016
##About
# Map Show
## About
Mapshow is a tool to display hdmap info on a map.
##Setup
If you run mapshow inside docker, there is no setup for running the tool. Otherwise, you have to run following command to setup python path.
## Setup
```
shell
source
setup.sh
If you run mapshow inside docker, there is no setup for running the tool.
Otherwise, you have to run following command to setup python path.
```
bash
# In apollo root dir:
source
scripts/apollo_base.sh
```
## Usage
...
...
@@ -26,20 +32,18 @@ source setup.sh
Show basic map layout only
```
```
bash
python mapshow.py
-m
/path/to/map/file
```
Show basic map layout with all lane ids
```
```
bash
python mapshow.py
-m
/path/to/map/file
-sl
```
show basic map layout with specific lane ids
```
```
bash
python mapshow.py
-m
/path/to/map/file
-l
1474023788152_1_-1
```
\ No newline at end of file
modules/tools/mapshow/localization.py
浏览文件 @
b98c0016
import
math
import
threading
from
google.protobuf
import
text_format
from
modules.localization.proto
import
localization_pb2
import
common.proto_utils
as
proto_utils
from
modules.localization.proto.localization_pb2
import
LocalizationEstimate
class
Localization
:
...
...
@@ -17,10 +16,8 @@ class Localization:
self
.
localization_data_lock
.
release
()
def
load
(
self
,
localization_file_name
):
self
.
localization_pb
=
localization_pb2
.
LocalizationEstimate
()
f_handle
=
open
(
localization_file_name
,
'r'
)
text_format
.
Merge
(
f_handle
.
read
(),
self
.
localization_pb
)
f_handle
.
close
()
self
.
localization_pb
=
proto_utils
.
get_pb_from_text_file
(
localization_file_name
,
LocalizationEstimate
())
def
plot_vehicle
(
self
,
ax
):
self
.
plot_vehicle_position
(
ax
)
...
...
modules/tools/mapshow/map.py
浏览文件 @
b98c0016
...
...
@@ -19,10 +19,10 @@
import
random
import
matplotlib.pyplot
as
plt
from
google.protobuf
import
text_format
from
matplotlib
import
cm
as
cmx
from
matplotlib
import
colors
as
mcolors
import
common.proto_utils
as
proto_utils
from
modules.map.proto
import
map_pb2
class
Map
:
...
...
@@ -43,20 +43,8 @@ class Map:
self
.
colors
.
append
(
color_val
)
def
load
(
self
,
map_file_name
):
try
:
f_handle
=
open
(
map_file_name
,
"rb"
)
self
.
map_pb
.
ParseFromString
(
f_handle
.
read
())
f_handle
.
close
()
return
True
except
Exception
as
e
:
try
:
f_handle
=
open
(
map_file_name
,
'r'
)
text_format
.
Merge
(
f_handle
.
read
(),
self
.
map_pb
)
f_handle
.
close
()
return
True
except
Exception
as
e
:
print
"Error: map file is incorrect!"
return
False
res
=
proto_utils
.
get_pb_from_file
(
map_file_name
,
self
.
map_pb
)
return
res
!=
None
def
draw_lanes
(
self
,
ax
,
is_show_lane_ids
,
laneids
):
cnt
=
1
...
...
modules/tools/perception/extend_prediction.py
浏览文件 @
b98c0016
...
...
@@ -8,26 +8,13 @@ import time
import
numpy
import
rospy
from
google.protobuf
import
text_format
from
std_msgs.msg
import
String
import
common.proto_utils
as
proto_utils
from
modules.prediction.proto.prediction_obstacle_pb2
import
PredictionObstacle
from
modules.prediction.proto.prediction_obstacle_pb2
import
PredictionObstacles
def
load_pb_from_file
(
filename
,
pb_value
):
"""load pb from file"""
try
:
f_handle
=
open
(
filename
,
"rb"
)
pb_value
.
ParseFromString
(
f_handle
.
read
())
f_handle
.
close
()
except
Exception
as
e
:
f_handle
=
open
(
filename
,
'r'
)
text_format
.
Merge
(
f_handle
.
read
(),
pb_value
)
f_handle
.
close
()
return
pb_value
def
distance
(
p1
,
p2
):
"""distance between two trajectory points"""
return
math
.
sqrt
((
p1
.
y
-
p2
.
y
)
**
2
+
(
p1
.
x
-
p2
.
x
)
**
2
);
...
...
@@ -80,6 +67,7 @@ if __name__ == '__main__':
parser
.
add_argument
(
"-d"
,
"--distance"
,
action
=
"store"
,
type
=
float
,
default
=
70.0
,
help
=
"set the prediction distance"
)
args
=
parser
.
parse_args
()
prediction_data
=
load_pb_from_file
(
args
.
prediction
,
PredictionObstacles
())
prediction_data
=
proto_utils
.
get_pb_from_file
(
args
.
prediction
,
PredictionObstacles
())
extended_prediction
=
extend_prediction
(
prediction_data
,
args
.
distance
,
args
.
period
)
print
extended_prediction
modules/tools/planning_traj_plot/main.py
浏览文件 @
b98c0016
...
...
@@ -18,30 +18,12 @@
import
sys
import
gflags
import
matplotlib.pyplot
as
plt
from
gflags
import
FLAGS
from
google.protobuf
import
text_format
import
common.proto_utils
as
proto_utils
import
mkz_polygon
from
modules.planning.proto
import
planning_pb2
from
modules.localization.proto
import
localization_pb2
def
read_planning_pb
(
planning_pb_file
):
planning_pb
=
planning_pb2
.
ADCTrajectory
()
f_handle
=
open
(
planning_pb_file
,
'r'
)
text_format
.
Merge
(
f_handle
.
read
(),
planning_pb
)
f_handle
.
close
()
return
planning_pb
def
read_localization_pb
(
localization_pb_file
):
localization_pb
=
localization_pb2
.
LocalizationEstimate
()
f_handle
=
open
(
localization_pb_file
,
'r'
)
text_format
.
Merge
(
f_handle
.
read
(),
localization_pb
)
f_handle
.
close
()
return
localization_pb
from
modules.planning.proto.planning_pb2
import
ADCTrajectory
from
modules.localization.proto.localization_pb2
import
LocalizationEstimate
def
plot_trajectory
(
planning_pb
,
ax
):
...
...
@@ -142,8 +124,10 @@ if __name__ == "__main__":
planning_pb_file
=
sys
.
argv
[
1
]
localization_pb_file
=
sys
.
argv
[
2
]
planning_pb
=
read_planning_pb
(
planning_pb_file
)
localization_pb
=
read_localization_pb
(
localization_pb_file
)
planning_pb
=
proto_utils
.
get_pb_from_text_file
(
planning_pb_file
,
ADCTrajectory
())
localization_pb
=
proto_utils
.
get_pb_from_text_file
(
localization_pb_file
,
LocalizationEstimate
())
plot_trajectory
(
planning_pb
,
plt
)
plot_vehicle
(
localization_pb
,
plt
)
...
...
modules/tools/planning_traj_plot/run.sh
浏览文件 @
b98c0016
...
...
@@ -24,6 +24,6 @@ then
fi
DIR
=
"
$(
cd
"
$(
dirname
"
${
BASH_SOURCE
[0]
}
"
)
"
&&
pwd
)
"
source
"
${
DIR
}
/../../../scripts/apollo_base.sh"
export
PYTHONPATH
=
"
${
DIR
}
/../../../bazel-genfiles:
${
PYTHONPATH
}
"
eval
"python
${
DIR
}
/main.py
$1
$2
"
scripts/apollo_base.sh
浏览文件 @
b98c0016
...
...
@@ -105,13 +105,16 @@ function set_lib_path() {
if
[
"
$RELEASE_DOCKER
"
==
1
]
;
then
source
/apollo/ros/setup.bash
export
LD_LIBRARY_PATH
=
$LD_LIBRARY_PATH
:/apollo/lib
export
PYTHONPATH
=
/apollo/lib:
${
PYTHONPATH
}
PY_LIB_PATH
=
/apollo/lib
PY_TOOLS_PATH
=
/apollo/modules/tools
else
if
[
-e
"
${
APOLLO_ROOT_DIR
}
/bazel-apollo/external/ros/setup.bash"
]
;
then
source
"
${
APOLLO_ROOT_DIR
}
/bazel-apollo/external/ros/setup.bash"
fi
export
PYTHONPATH
=
${
APOLLO_ROOT_DIR
}
/bazel-genfiles:
${
PYTHONPATH
}
PY_LIB_PATH
=
${
APOLLO_ROOT_DIR
}
/bazel-genfiles
PY_TOOLS_PATH
=
${
APOLLO_ROOT_DIR
}
/modules/tools
fi
export
PYTHONPATH
=
${
PY_LIB_PATH
}
:
${
PY_TOOLS_PATH
}
:
${
PYTHONPATH
}
}
function
create_data_dir
()
{
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录