Skip to content
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
26 changes: 26 additions & 0 deletions config/camera/c1_camera.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
image_width: 1920
image_height: 1280
camera_name: narrow_stereo
camera_matrix:
rows: 3
cols: 3
data: [859.59833, 0. , 957.65917,
0. , 905.13896, 644.25074,
0. , 0. , 1. ]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.141101, 0.023163, -0.004701, -0.003043, 0.000000]
rectification_matrix:
rows: 3
cols: 3
data: [1., 0., 0.,
0., 1., 0.,
0., 0., 1.]
projection_matrix:
rows: 3
cols: 4
data: [701.62775, 0. , 936.96648, 0. ,
0. , 836.91895, 635.76492, 0. ,
0. , 0. , 1. , 0. ]
2 changes: 1 addition & 1 deletion config/scan_segmentation.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,4 +8,4 @@ perception:
distance_ratio : 2.0
theta_threashold : 0.3141592653589793
output_frame_id : "base_link"
visualize_frame_id : "map"
visualize_frame_id : "base_link"
30 changes: 30 additions & 0 deletions config/urdf/miniv_sensors.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from miniv_sensors.xacro.urdf | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="miniv_sensors">
<link name="base_link">
</link>
<link name="front_velodyne">
</link>
<link name="front_camera_link">
</link>
<link name="front_camera_optical_link">
</link>
<joint name="front_velodyne_to_camera_joint" type="fixed">
<parent link="front_velodyne"/>
<child link="front_camera_link"/>
<origin rpy="3.141592653589793 0 0" xyz="0.05 0 -0.08"/>
</joint>
<joint name="front_camera_to_camera_optical_joint" type="fixed">
<parent link="front_camera_link"/>
<child link="front_camera_optical_link"/>
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
</joint>
<joint name="front_base_link_to_velodyne_joint" type="fixed">
<parent link="base_link"/>
<child link="front_velodyne"/>
<origin rpy="3.141592653589793 0 0" xyz="0.2 0 0.1"/>
</joint>
</robot>
6 changes: 6 additions & 0 deletions config/urdf/miniv_sensors.xacro.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="miniv_sensors">
<xacro:include filename="sensor_mount.xacro.urdf"/>

<xacro:property name="sensor_prefix" value="front"/>
<xacro:sensor_mount prefix="${sensor_prefix}"/>
</robot>
36 changes: 36 additions & 0 deletions config/urdf/sensor_mount.xacro.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="sensor_mount">

<xacro:macro name="sensor_mount" params="prefix:=sensor">
<link name="base_link">
</link>

<link name="${prefix}_velodyne">
</link>

<link name="${prefix}_camera_link">
</link>

<link name="${prefix}_camera_optical_link">
</link>

<joint name="${prefix}_velodyne_to_camera_joint" type="fixed">
<parent link="${prefix}_velodyne"/>
<child link="${prefix}_camera_link"/>
<origin xyz="0.05 0 -0.08" rpy="${pi} 0 0"/>
</joint>

<joint name="${prefix}_camera_to_camera_optical_joint" type="fixed">
<parent link="${prefix}_camera_link"/>
<child link="${prefix}_camera_optical_link"/>
<origin xyz="0 0 0" rpy="-${pi/2} 0 -${pi/2}"/>
</joint>

<joint name="${prefix}_base_link_to_velodyne_joint" type="fixed">
<parent link="base_link"/>
<child link="${prefix}_velodyne"/>
<origin xyz="0.2 0 0.1" rpy="${pi} 0 0"/>
</joint>

</xacro:macro>
</robot>
22 changes: 22 additions & 0 deletions config/velodyne/front_lidar_nebula_driver.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
/**:
ros__parameters:
host_ip: 192.168.0.200
sensor_ip: 192.168.0.201
data_port: 2368
gnss_port: 2369
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
frame_id: front_velodyne
advanced_diagnostics: false
diag_span: 1000
calibration_file: $(find-pkg-share nebula_decoders)/calibration/velodyne/VLP16.yaml
min_range: 0.3
max_range: 300.0
cloud_min_angle: 0
cloud_max_angle: 360
scan_phase: 0.0
sensor_model: VLP16
rotation_speed: 600
return_mode: Dual
14 changes: 14 additions & 0 deletions dependency-humble.repos
Original file line number Diff line number Diff line change
Expand Up @@ -51,3 +51,17 @@ repositories:
type: git
url: https://github.com/OUXT-Polaris/detic_onnx_ros2
version: master
# TCP version of transport drivers
transport_drivers:
type: git
url: https://github.com/autowarefoundation/transport_drivers
version: main
# Continental compatible version of ROS 2 socket CAN
ros2_socketcan:
type: git
url: https://github.com/autowarefoundation/ros2_socketcan
version: main
nebula:
type: git
url: https://github.com/tier4/nebula.git
version: main
3 changes: 3 additions & 0 deletions launch/logger.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
source /opt/ros/humble/setup.bash
source /home/ubuntu/ouxt_automation/robotx_ws/install/local_setup.bash
ros2 bag record -o /home/ubuntu/auto_logger/rosbag/$(date '+%Y-%m-%d-%H-%M-%S') -d 10 -s mcap --storage-config-file /home/ubuntu/ouxt_automation/.github/workflows/docker/auto_logger/settings/storage_options.yaml /wamv/sensors/cameras/front_camera_sensor/image_raw/compressed /wamv/sensors/lidars/front_lidar_sensor/velodyne_points /protolink/gps/geopose
32 changes: 32 additions & 0 deletions launch/miniv_perception_bringup.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
<launch>
<arg name="use_sim_time" default="false"/>

<include file="$(find-pkg-share perception_bringup)/launch/sensor_mount_bringup.launch.xml">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
</include>

<node_container pkg="rclcpp_components" exec="component_container_mt" name="perception_container" namespace="perception" args="perception">
<composable_node pkg="pcl_apps" plugin="pcl_apps::PointCloudToLaserScanComponent" name="pointcloud_to_laserscan_node" namespace="perception">
<param name="use_sim_time" value="$(var use_sim_time)"/>
<param name="use_intra_process_comms" value="true"/>
<remap from="input" to="/wamv/sensors/lidars/$(var prefix)_lidar_sensor/velodyne_points"/>
<remap from="output" to="pointcloud_to_laserscan_node/output"/>
</composable_node>

<composable_node pkg="scan_segmentation" plugin="scan_segmentation::ScanSegmentationComponent" name="scan_segmentation_node" namespace="perception">
<param name="use_sim_time" value="$(var use_sim_time)"/>
<param name="use_intra_process_comms" value="true"/>
<param from="$(find-pkg-share perception_bringup)/config/scan_segmentation.yaml"/>
</composable_node>
</node_container>

<executable cmd="/home/ubuntu/ouxt_automation/robotx_ws/src/perception/perception_bringup/launch/logger.sh" output="screen" shell="true" />

<!-- <group>
<push_ros_namespace namespace="perception" />
<include file="$(find-pkg-share detic_onnx_ros2)/detic_onnx_ros2.launch.xml">
<arg name="input_topic" value="/wamv/sensors/cameras/front_camera_sensor/image_raw"/>
<arg name="detection_width" value="1080"/>
</include>
</group> -->
</launch>
43 changes: 43 additions & 0 deletions launch/sensor_mount_bringup.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
<launch>
<arg name="use_sim_time" default="false"/>
<arg name="prefix" default="front"/>
<arg name="model" default="$(find-pkg-share perception_bringup)/config/urdf/miniv_sensors.urdf"/>
<arg name="publish_tf" default="true"/>

<arg name="vlp16_config_file" default="$(find-pkg-share perception_bringup)/config/velodyne/$(var prefix)_lidar_nebula_driver.yaml"/>

<node_container pkg="rclcpp_components" exec="component_container_mt" name="sensing_container" namespace="sensing" args="sensing/$(var prefix)_sensor">
<!-- Camera Driver -->
<composable_node pkg="v4l2_camera" plugin="v4l2_camera::V4L2Camera" name="driver_node" namespace="sensing/$(var prefix)_camera">
<param name="use_sim_time" value="$(var use_sim_time)"/>
<param name="use_intra_process_comms" value="true"/>
<remap from="image_raw" to="/wamv/sensors/cameras/$(var prefix)_camera_sensor/image_raw"/>
<remap from="camera_info" to="/wamv/sensors/cameras/$(var prefix)_camera_sensor/camera_info"/>
<remap from="image_raw/compressed" to="/wamv/sensors/cameras/$(var prefix)_camera_sensor/image_raw/compressed"/>
<param name="camera_info_url" value="file://$(find-pkg-share perception_bringup)/config/camera/c1_camera.yaml"/>
<param name="camera_frame_id" value="$(var prefix)_camera_optical_link"/>
<param name="video_device" value="/dev/video0"/>
<param name="use_image_transport" value="true"/>
<param name="image_raw.enable_pub_plugin" value="image_transport/compressed"/>
<!-- <param name="image_raw.enable_pub_plugin" value="image_transport/compressed"/> -->
</composable_node>

<!-- Velodyne Driver -->
<composable_node pkg="nebula_ros" plugin="VelodyneRosWrapper" name="velodyne_driver" namespace="sensing/$(var prefix)_lidar">
<param name="use_sim_time" value="$(var use_sim_time)"/>
<param name="use_intra_process_comms" value="true"/>
<param from="$(var vlp16_config_file)" allow_substs="true"/>
<param name="launch_hw" value="true"/>
<remap from="velodyne_points" to="/wamv/sensors/lidars/$(var prefix)_lidar_sensor/velodyne_points"/>
<remap from="velodyne_packets" to="/wamv/sensors/lidars/$(var prefix)_lidar_sensor/velodyne_packets"/>
<remap from="aw_points_ex" to="/wamv/sensors/lidars/$(var prefix)_lidar_sensor/aw_points_ex"/>
<remap from="aw_points" to="/wamv/sensors/lidars/$(var prefix)_lidar_sensor/aw_points"/>
</composable_node>
</node_container>

<group if="$(var publish_tf)">
<node name="robot_state_publisher" pkg="robot_state_publisher" exec="robot_state_publisher">
<param name="robot_description" value="$(command 'xacro $(var model)')"/>
</node>
</group>
</launch>
2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,10 @@
<exec_depend>image_processing_utils</exec_depend>
<exec_depend>velodyne_pointcloud</exec_depend>
<exec_depend>velodyne_driver</exec_depend>
<exec_depend>image_transport_plugins</exec_depend>
<exec_depend>topic_tools</exec_depend>
<exec_depend>rosbag2_transport</exec_depend>
<exec_depend>nebula_ros</exec_depend>

<test_depend>ouxt_lint_common</test_depend>

Expand Down
Loading