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

Changed by tomoki #2

Open
wants to merge 14 commits into
base: main
Choose a base branch
from
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
thresholds:
interval: 100.0
relative_angle: 2.0 # (= 115 degree)
curvature: 1.0
curvature: 100.0
lateral_acc: 9.8
longitudinal_max_acc: 9.8
longitudinal_min_acc: -9.8
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,16 +2,16 @@
/**:
ros__parameters:
avoidance:
resample_interval_for_planning: 0.3 # [m]
resample_interval_for_output: 4.0 # [m]
resample_interval_for_planning: 0.1 # [m]
resample_interval_for_output: 0.5 # [m]
detection_area_right_expand_dist: 0.0 # [m]
detection_area_left_expand_dist: 1.0 # [m]
detection_area_left_expand_dist: 0.0 # [m]
drivable_area_right_bound_offset: 0.0 # [m]
drivable_area_left_bound_offset: 0.0 # [m]
object_envelope_buffer: 0.3 # [m]
object_envelope_buffer: 0.0 # [m]

# avoidance module common setting
enable_bound_clipping: false
enable_bound_clipping: true
enable_avoidance_over_same_direction: true
enable_avoidance_over_opposite_direction: true
enable_update_path_when_object_is_gone: false
Expand All @@ -30,8 +30,8 @@
truck: true
bus: true
trailer: true
unknown: false
bicycle: false
unknown: true
bicycle: true
motorcycle: false
pedestrian: false

Expand All @@ -51,7 +51,7 @@
object_check_shiftable_ratio: 0.6 # [-]
object_check_min_road_shoulder_width: 0.5 # [m]
# lost object compensation
object_last_seen_threshold: 2.0
object_last_seen_threshold: 0.0

# For safety check
safety_check:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,6 @@ Panels:
- /Perception1
- /Perception1/Segmentation1
- /Perception1/ObjectRecognition1
- /Perception1/ObjectRecognition1/Detection1
- /Perception1/ObjectRecognition1/Detection1/DetectedObjects1/CAR1
- /Perception1/ObjectRecognition1/Tracking1/TrackedObjects1
- /Planning1/ScenarioPlanning1
- /Behavior_Path1/View Path1
Expand Down Expand Up @@ -727,7 +725,7 @@ Visualization Manager:
Color: 119; 11; 32
Class: autoware_auto_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: false
Display Label: true
Display PoseWithCovariance: true
Display Predicted Path Confidence: true
Display Predicted Paths: true
Expand All @@ -741,6 +739,8 @@ Visualization Manager:
Color: 119; 11; 32
Name: DetectedObjects
Namespaces:

label: true
shape: true
twist: true
velocity: true
Expand Down Expand Up @@ -794,6 +794,7 @@ Visualization Manager:
Color: 119; 11; 32
Name: TrackedObjects
Namespaces:

acceleration: true
label: true
position covariance: true
Expand Down Expand Up @@ -822,7 +823,8 @@ Visualization Manager:
Color: 255; 255; 255
Value: true
Visualization Type: Normal
Enabled: true

Enabled: false
Name: Tracking
- Class: rviz_common/Group
Displays:
Expand Down Expand Up @@ -2144,7 +2146,8 @@ Visualization Manager:
Name: Control
- Class: rviz_plugins/Path
Color Border Vel Max: 3
Enabled: true

Enabled: false
Name: Behavior_Path
Topic:
Depth: 5
Expand All @@ -2153,7 +2156,7 @@ Visualization Manager:
History Policy: Keep Last
Reliability Policy: Reliable
Value: /planning/scenario_planning/lane_driving/behavior_planning/path
Value: true
Value: false
View Drivable Area:
Alpha: 0.9990000128746033
Color: 0; 148; 205
Expand Down Expand Up @@ -2319,7 +2322,7 @@ Visualization Manager:
Value: true
Views:
Current:
Angle: 0.43000009655952454
Angle: 0.4750000238418579
Class: rviz_default_plugins/TopDownOrtho
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Expand All @@ -2329,11 +2332,11 @@ Visualization Manager:
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Scale: 55.90018844604492
Scale: 85.11080169677734
Target Frame: viewer
Value: TopDownOrtho (rviz_default_plugins)
X: 53.38139343261719
Y: 13.1110258102417
X: 45.90351104736328
Y: 10.50330924987793
Saved:
- Class: rviz_default_plugins/ThirdPersonFollower
Distance: 18
Expand Down Expand Up @@ -2382,7 +2385,7 @@ Window Geometry:
Hide Right Dock: false
InitialPoseButtonPanel:
collapsed: false
QMainWindow State: 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
QMainWindow State: 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
RecognitionResultOnImage:
collapsed: false
Selection:
Expand All @@ -2392,5 +2395,5 @@ Window Geometry:
Views:
collapsed: false
Width: 1436
X: 2298
X: 2404
Y: 27
1 change: 1 addition & 0 deletions docker/aichallenge/do.bash
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#! /usr/bin/bash

export ROS_LOCALHOST_ONLY=1
bash /aichallenge/run.sh & /aichallenge/AWSIM/AWSIM.x86_64
55 changes: 55 additions & 0 deletions docker/aichallenge/lidar_centerpoint_visualizer.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
#!/usr/bin/env python
# Copyright 2022 TIER IV, Inc. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import os
import time

import open3d as o3d
import rclpy
from rclpy.node import Node


def main(args=None):
rclpy.init(args=args)

node = Node("lidar_centerpoint_visualizer")
node.declare_parameter("pcd_path", rclpy.Parameter.Type.STRING)
node.declare_parameter("detections_path", rclpy.Parameter.Type.STRING)

pcd_path = node.get_parameter("pcd_path").get_parameter_value().string_value
detections_path = node.get_parameter("detections_path").get_parameter_value().string_value

while not os.path.exists(pcd_path) and not os.path.exists(detections_path):
time.sleep(1.0)

if not rclpy.ok():
rclpy.shutdown()
return

mesh = o3d.io.read_triangle_mesh(detections_path)
pcd = o3d.io.read_point_cloud(pcd_path)

mesh_frame = o3d.geometry.TriangleMesh.create_coordinate_frame(size=1.0, origin=[0, 0, 0])

detection_lines = o3d.geometry.LineSet.create_from_triangle_mesh(mesh)
detection_lines.paint_uniform_color([1.0, 0.0, 1.0])

o3d.visualization.draw_geometries([mesh_frame, pcd, detection_lines])

rclpy.shutdown()


if __name__ == "__main__":
main()