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

170 feature setup object and distance detection for multiple cameras #196

Closed
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 code/agent/config/dev_objects.json
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
},
{
"type": "sensor.camera.rgb",
"id": "Left",
"id": "Right",
"spawn_point": {
"x": 0.0,
"y": 0.0,
Expand All @@ -64,7 +64,7 @@
},
{
"type": "sensor.camera.rgb",
"id": "Right",
"id": "Left",
"spawn_point": {
"x": 0.0,
"y": 0.0,
Expand Down
1 change: 0 additions & 1 deletion code/agent/launch/agent.launch
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,5 @@
<arg name="role_name" value="$(arg role_name)"/>
</include>


<node type="rviz" name="rviz" pkg="rviz" args="-d $(find agent)/config/rviz_config.rviz" />
</launch>
79 changes: 62 additions & 17 deletions code/agent/src/agent/agent.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
from leaderboard.autoagents.ros1_agent import ROS1Agent
from leaderboard.autoagents.autonomous_agent import Track
import math


def get_entry_point():
Expand All @@ -22,23 +23,67 @@ def get_ros_entrypoint(self):

def sensors(self):
sensors = [
{'type': 'sensor.camera.rgb', 'id': 'Center',
'x': 0.0, 'y': 0.0, 'z': 1.70, 'roll': 0.0, 'pitch': 0.0,
'yaw': 0.0, 'width': 1280, 'height': 720, 'fov': 100},
{'type': 'sensor.lidar.ray_cast', 'id': 'LIDAR',
'x': 0.0, 'y': 0.0, 'z': 1.70, 'roll': 0.0, 'pitch': 0.0,
'yaw': 0.0},
{'type': 'sensor.other.radar', 'id': 'RADAR',
'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,
'yaw': -45.0, 'horizontal_fov': 30, 'vertical_fov': 30},
{'type': 'sensor.other.gnss', 'id': 'GPS',
'x': 0.7, 'y': -0.4, 'z': 1.60},
{'type': 'sensor.other.imu', 'id': 'IMU',
'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,
'yaw': 0.0},
{'type': 'sensor.opendrive_map', 'id': 'OpenDRIVE',
'reading_frequency': 1},
{'type': 'sensor.speedometer', 'id': 'Speed'},
{
'type': 'sensor.camera.rgb',
'id': 'Center',
'x': 0.0, 'y': 0.0, 'z': 1.70,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
'width': 1280, 'height': 720, 'fov': 100
},
{
'type': 'sensor.camera.rgb',
'id': 'Back',
'x': 0.0, 'y': 0.0, 'z': 1.70,
'roll': 0.0, 'pitch': 0.0, 'yaw': math.radians(180.0),
'width': 1280, 'height': 720, 'fov': 100
},
{
'type': 'sensor.camera.rgb',
'id': 'Left',
'x': 0.0, 'y': 0.0, 'z': 1.70,
'roll': 0.0, 'pitch': 0.0, 'yaw': math.radians(-90.0),
'width': 1280, 'height': 720, 'fov': 100
},
{
'type': 'sensor.camera.rgb',
'id': 'Right',
'x': 0.0, 'y': 0.0, 'z': 1.70,
'roll': 0.0, 'pitch': 0.0, 'yaw': math.radians(90.0),
'width': 1280, 'height': 720, 'fov': 100
},
{
'type': 'sensor.lidar.ray_cast',
'id': 'LIDAR',
'x': 0.0, 'y': 0.0, 'z': 1.70,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0
},
{
'type': 'sensor.other.radar',
'id': 'RADAR',
'x': 0.7, 'y': -0.4, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0,
'horizontal_fov': 30, 'vertical_fov': 30
},
{
'type': 'sensor.other.gnss',
'id': 'GPS',
'x': 0.7, 'y': -0.4, 'z': 1.60
},
{
'type': 'sensor.other.imu',
'id': 'IMU',
'x': 0.7, 'y': -0.4, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0
},
{
'type': 'sensor.opendrive_map',
'id': 'OpenDRIVE',
'reading_frequency': 1
},
{
'type': 'sensor.speedometer',
'id': 'Speed'
}
]
return sensors

Expand Down
20 changes: 9 additions & 11 deletions code/perception/launch/perception.launch
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,12 @@
<node pkg="perception" type="vision_node.py" name="VisionNode" output="screen">
<param name="role_name" value="$(arg role_name)" />
<param name="side" value="Center" />

<!--
Object-Detection:
<param name="center" value="True" />
<param name="back" value="False" />
<param name="left" value="False" />
<param name="right" value="False" />

<!--Object-Detection:
- fasterrcnn_resnet50_fpn_v2
- fasterrcnn_mobilenet_v3_large_320_fpn
- yolov8n
Expand All @@ -59,7 +62,7 @@
Image-Segmentation:
- deeplabv3_resnet101
- yolov8x-seg
-->
-->

<param name="model" value="rtdetr-x" />
</node>
Expand All @@ -76,16 +79,11 @@
</node>

<node pkg="perception" type="lidar_distance.py" name="lidar_distance" output="screen">
<param name="max_y" value="2.5"/>
<param name="min_y" value="-2.5"/>
<param name="min_x" value="1."/>
<param name="min_z" value="-1.6"/>
<param name="max_z" value="1."/>
<param name="point_cloud_topic" value="/carla/hero/LIDAR_filtered"/>
<param name="range_topic" value="/carla/hero/LIDAR_range"/>
</node>

<node pkg="perception" type="lidar_distance.py" name="lidar_distance_rear_right" output="screen">
<!--<node pkg="perception" type="lidar_distance.py" name="lidar_distance_rear_right" output="screen">
<param name="min_y" value="-5"/>
<param name="max_y" value="-2.5"/>
<param name="max_x" value="0"/>
Expand All @@ -104,5 +102,5 @@
<param name="point_cloud_topic" value="/carla/hero/LIDAR_filtered_rear_left"/>
<param name="range_topic" value="/carla/hero/LIDAR_range_rear_left"/>
</node>

-->
</launch>
Loading
Loading