Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix perception offline visualizer #1

Open
wants to merge 2 commits into
base: simulator
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions .gitmodules
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[submodule "lg_pkgs/lgsvl_msgs"]
path = lgsvl_pkgs/lgsvl_msgs
url = ../lgsvl_msgs.git
url = https://github.com/lgsvl/lgsvl_msgs.git
branch = apollo_3_5
[submodule "modules/map/data/san_francisco"]
path = modules/map/data/san_francisco
url = ../apollo-simulator-map.git
url = https://github.com/lgsvl/apollo-simulator-map.git
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ To launch apollo, first launch and enter a container as described in the previou
* Open Apollo dreamview in a browser by navigating to: `localhost:8888`
- Select the `XE_Rigged_Apollo3.5` vehicle and `San Francisco` map in the top right corner.
- Open the **Module Controller** tab (on the left bar).
- Enable **Localization**, **Transform**, **Perception**, **Traffic Light**, **Planning**, **Prediction**, **Routing**.
- Enable **Localization**, **Transform**, **Perception**, **Prediction**, **Routing**, **Planning**.
- Navigate to the **Route Editing** tab.
- Select a destination by clicking on a lane line and clicking **Submit Route**.
- Enable **Control** in **Module Controller** tab.
Expand Down
7 changes: 0 additions & 7 deletions modules/common/data/vehicle_param.pb.txt
Original file line number Diff line number Diff line change
@@ -1,8 +1,4 @@
vehicle_param {
brand: LINCOLN_MKZ
vehicle_id {
other_unique_id: "mkz7"
}
front_edge_to_center: 3.705
back_edge_to_center: 0.995
left_edge_to_center: 1.03
Expand All @@ -19,7 +15,4 @@ vehicle_param {
steer_ratio: 11.4213198
wheel_base: 2.837007
wheel_rolling_radius: 0.33

brake_deadzone: 15.5
throttle_deadzone: 18.0
}
2 changes: 2 additions & 0 deletions modules/control/conf/navigation_lincoln.pb.txt
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,8 @@ lat_controller_conf {
}
lon_controller_conf {
ts: 0.01
brake_deadzone: 15.5
throttle_deadzone: 18.0
speed_controller_input_limit: 2.0
station_error_limit: 2.0
preview_window: 20.0
Expand Down
243 changes: 243 additions & 0 deletions modules/drivers/velodyne/params/128E_S3_calibration.yaml

Large diffs are not rendered by default.

4 changes: 4 additions & 0 deletions modules/drivers/velodyne/params/velodyne128_height.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
vehicle:
parameters:
height: 1.91
height_var: 0.0047
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: novatel
child_frame_id: velodyne128
transform:
translation:
x: 0
y: 0.9807289
z: 2.312
rotation:
x: 0
y: 0
z: 0.7071068
w: 0.7071068

4 changes: 4 additions & 0 deletions modules/drivers/velodyne/params/velodyne64_height.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
vehicle:
parameters:
height: 1.91
height_var: 0.0047

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
vehicle:
parameters:
height: 1.91
height_var: 0.0047
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: novatel
child_frame_id: velodyne128
transform:
translation:
x: 0
y: 0.9807289
z: 2.312
rotation:
x: 0
y: 0
z: 0.7071068
w: 0.7071068

243 changes: 243 additions & 0 deletions modules/perception/data/params/128E_S3_calibration.yaml

Large diffs are not rendered by default.

243 changes: 243 additions & 0 deletions modules/perception/data/params/64E_S3_calibration_example.yaml

Large diffs are not rendered by default.

5 changes: 1 addition & 4 deletions modules/perception/data/params/front_6mm_extrinsics.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,4 @@ transform:
y: -0.5
z: 0.5
w: -0.5
euler_angles_degree:
pitch: -90.0
yaw: -90.0
roll: 0.0

17 changes: 17 additions & 0 deletions modules/perception/data/params/radar_extrinsics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: front_6mm
child_frame_id: radar
transform:
translation:
x: 0
y: 1.011
z: 2.472
rotation:
x: 0.5
y: -0.5
z: 0.5
w: 0.5
18 changes: 18 additions & 0 deletions modules/perception/data/params/radar_front_extrinsics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: velodyne128
child_frame_id: radar_front
transform:
translation:
x: 2.63992
y: 0
z: -1.623
rotation:
x: 0
y: 0
z: 0
w: 1

67 changes: 67 additions & 0 deletions modules/perception/data/params/start_leopard.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
<launch>
<arg name="traffic_short_topic_name" default="/apollo/sensor/camera/traffic/image_short" />
<arg name="traffic_long_topic_name" default="/apollo/sensor/camera/traffic/image_long" />
<arg name="front_obstacle_6mm_topic_name" default="/apollo/sensor/camera/obstacle/front_6mm" />
<arg name="frame_rate" default="30"/>

<group ns="camera_long">
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" respawn="true" />

<node pkg="nodelet" type="nodelet" name="sensor_camera_traffic_long" output="screen"
args="load usb_cam/UsbCamNodelet camera_nodelet_manager" respawn="true" >
<param name="video_device" value="/dev/camera/trafficlights" />
<param name="image_width" value="1920" />
<param name="image_height" value="1080" />
<param name="pixel_format" value="rgb24" />
<param name="frame_rate" value="$(arg frame_rate)" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="camera_timeout" value="2000" />
<param name="error_code" value="11" />
<param name="camera_info_url" type="string" value="long_camera_intrinsics.yaml" />
<remap from="/camera_long/image_raw0" to="$(arg traffic_long_topic_name)" />
<remap from="/apollo/sensor/camera/traffic/camera_info" to="$(arg traffic_long_topic_name)/camera_info" />
</node>
</group>

<group ns="camera_short">
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" respawn="true" />

<node pkg="nodelet" type="nodelet" name="sensor_camera_traffic_short" output="screen"
args="load usb_cam/UsbCamNodelet camera_nodelet_manager" respawn="true" >
<param name="video_device" value="/dev/camera/obstacle" />
<param name="image_width" value="1920" />
<param name="image_height" value="1080" />
<param name="pixel_format" value="rgb24" />
<param name="frame_rate" value="$(arg frame_rate)" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="camera_timeout" value="2000" />
<param name="error_code" value="14" />
<param name="camera_info_url" type="string" value="short_camera_intrinsics.yaml" />
<remap from="/camera_short/image_raw0" to="$(arg traffic_short_topic_name)" />
<remap from="/apollo/sensor/camera/traffic/camera_info" to="$(arg traffic_short_topic_name)/camera_info" />
</node>
</group>

<group ns="camera_obstacle">
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" respawn="true" />

<node pkg="nodelet" type="nodelet" name="sensor_camera_obstacle" output="screen"
args="load usb_cam/UsbCamNodelet camera_nodelet_manager" respawn="true" >
<param name="video_device" value="/dev/camera/lanemark" />
<param name="image_width" value="1920" />
<param name="image_height" value="1080" />
<param name="pixel_format" value="rgb24" />
<param name="frame_rate" value="$(arg frame_rate)" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="camera_timeout" value="2000" />
<param name="error_code" value="14" />
<param name="camera_info_url" type="string" value="front_camera_intrinsics.yaml" />
<remap from="/camera_obstacle/image_raw0" to="$(arg front_obstacle_6mm_topic_name)" />
<remap from="/apollo/sensor/camera/traffic/camera_info" to="$(arg front_obstacle_6mm_topic_name)/camera_info" />
</node>
</group>

</launch>
26 changes: 26 additions & 0 deletions modules/perception/data/params/start_obstacle_camera.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<launch>
<arg name="front_obstacle_6mm_topic_name" default="/apollo/sensor/camera/obstacle/front_6mm" />
<arg name="frame_rate" default="30"/>


<group ns="camera_obstacle">
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" respawn="true" />

<node pkg="nodelet" type="nodelet" name="sensor_camera_obstacle" output="screen"
args="load usb_cam/UsbCamNodelet camera_nodelet_manager" respawn="true" >
<param name="video_device" value="/dev/camera/lanemark" />
<param name="image_width" value="1920" />
<param name="image_height" value="1080" />
<param name="pixel_format" value="rgb24" />
<param name="frame_rate" value="$(arg frame_rate)" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="camera_timeout" value="2000" />
<param name="error_code" value="14" />
<param name="camera_info_url" type="string" value="front_camera_intrinsics.yaml" />
<remap from="/camera_obstacle/image_raw0" to="$(arg front_obstacle_6mm_topic_name)" />
<remap from="/apollo/sensor/camera/traffic/camera_info" to="$(arg front_obstacle_6mm_topic_name)/camera_info" />
</node>
</group>

</launch>
4 changes: 4 additions & 0 deletions modules/perception/data/params/velodyne128_height.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
vehicle:
parameters:
height: 1.91
height_var: 0.0047
18 changes: 18 additions & 0 deletions modules/perception/data/params/velodyne128_novatel_extrinsics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: novatel
child_frame_id: velodyne128
transform:
translation:
x: 0
y: 0.9807289
z: 2.312
rotation:
x: 0
y: 0
z: 0.7071068
w: 0.7071068

4 changes: 4 additions & 0 deletions modules/perception/data/params/velodyne64_height.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
vehicle:
parameters:
height: 1.91
height_var: 0.0047
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: novatel
child_frame_id: velodyne64
transform:
translation:
x: 0
y: 0.9807289
z: 2.312
rotation:
x: 0
y: 0
z: 0.7071068
w: 0.7071068

Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ image_channel_num : 3
enable_undistortion : false
enable_visualization : true
output_final_obstacles : true
output_obstacles_channel_name : "/perception/obstacles"
output_obstacles_channel_name : "/apollo/perception/obstacles"
camera_perception_viz_message_channel_name : "/perception/inner/camera_viz_msg"
prefused_channel_name : "/perception/inner/PrefusedObjects"
default_camera_pitch : 0.0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
model_param {
model_name: "./3d-r4-half"
model_type: "RTNetInt8"
#model_type: "RTNetInt8"
model_type: "CaffeNet"
weight_file: "deploy.model"
proto_file: "deploy.pt"
anchors_file: "anchors.txt"
types_file: "types.txt"
calibratetable_root: "./3d-r4-half"
#calibratetable_root: "./3d-r4-half"
confidence_threshold: 0.4
offset_ratio: 0.288889
cropped_ratio: 0.711111
Expand Down
17 changes: 12 additions & 5 deletions scripts/perception_offline_visualizer.sh
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,18 @@
# limitations under the License.
###############################################################################


DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"

source "${DIR}/apollo_base.sh"
# run function from apollo_base.sh
# run command_name module_name
run perception "$@" --dag_config_path=/apollo/modules/perception/conf/dag_camera_obstacle_vis.config \
--alsologtostderr=1 --v=4

if [ $# -ne 1 ] ; then
echo "usage $0 start/stop"
exit 1;
fi

cmd=$1

cyber_launch $cmd /apollo/modules/perception/production/launch/perception_camera.launch
cyber_launch $cmd /apollo/modules/perception/production/launch/perception_trafficlight_vis.launch
cyber_launch $cmd /apollo/modules/drivers/tools/image_decompress/launch/image_decompress.launch
cyber_launch $cmd /apollo/modules/transform/launch/static_transform.launch