Skip to content

Commit

Permalink
Merge branch 'main' into generic-hesai-decoder
Browse files Browse the repository at this point in the history
  • Loading branch information
amc-nu authored Sep 5, 2023
2 parents 51e1ce1 + e0d05a7 commit 45df6b6
Show file tree
Hide file tree
Showing 11 changed files with 30 additions and 27 deletions.
10 changes: 9 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,17 @@
Nebula is a sensor driver platform that is designed to provide a unified framework for as wide a variety of devices as possible.
While it primarily targets Ethernet-based LiDAR sensors, it aims to be easily extendable to support new sensors and interfaces.
Nebula provides the following features:
- Support for Velodyne and Hesai sensors, with other LiDAR vendor support under development
- ROS 2 interface implementations
- Abstraction of sensor decoders and hardware interfaces available as libraries
- TCP/IP and UDP communication implementations
- Abstraction of sensor decoders and hardware interfaces available as libraries
- Handling of standard LiDAR functionality, including but not limited to:
- Configuration of communication settings such as sensor and host IP addresses and communication ports
- Configuration of scan speed, synchronization settings, scan phase, and field of view
- Receiving and conversion of UDP packet data into point clouds in Cartesian co-ordinates
- Receiving and interpretation of diagnostics information from the sensor
- Support for multiple return modes and labelling of return types for each point


With a rapidly increasing number of sensor types and models becoming available, and varying levels of vendor and third-party driver support, Nebula creates a centralized driver methodology. We hope that this project will be used to facilitate active collaboration and efficiency in development projects by providing a platform that reduces the need to re-implement and maintain many different sensor drivers. Contributions to extend the supported devices and features of Nebula are always welcome.

Expand Down
1 change: 1 addition & 0 deletions nebula_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
<author>Tier IV</author>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>ros_environment</buildtool_depend>

<depend>libpcl-all-dev</depend>
<depend>pcl_conversions</depend>
Expand Down
1 change: 1 addition & 0 deletions nebula_decoders/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
<author>Tier IV</author>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>ros_environment</buildtool_depend>

<depend>angles</depend>
<depend>libpcl-all-dev</depend>
Expand Down
1 change: 1 addition & 0 deletions nebula_examples/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
<author>Tier IV</author>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>ros_environment</buildtool_depend>

<depend>diagnostic_msgs</depend>
<depend>diagnostic_updater</depend>
Expand Down
4 changes: 2 additions & 2 deletions nebula_messages/pandar_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,13 @@
<name>pandar_msgs</name>
<version>0.0.0</version>
<description>
ROS message definition for the Heisai PandarQT/Pandar64/Pandar40P/Pandar20A/Pandar20B/Pandar40M LiDAR
ROS message definition for the Hesai PandarQT/Pandar64/Pandar40P/Pandar20A/Pandar20B/Pandar40M LiDAR
sensor.
</description>
<maintainer email="[email protected]">hirakawa</maintainer>
<license>Apache 2</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>

<depend>builtin_interfaces</depend>
Expand Down
2 changes: 1 addition & 1 deletion nebula_messages/velodyne_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<maintainer email="[email protected]">Perception Engine</maintainer>
<license>BSD</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>

<depend>std_msgs</depend>
Expand Down
25 changes: 5 additions & 20 deletions nebula_ros/config/velodyne/VLP32.yaml
Original file line number Diff line number Diff line change
@@ -1,25 +1,10 @@
#nebula_velodyne_hw_interface:
#nebula_velodyne_hw_monitor:
/**:
ros__parameters:
sensor_model: "VLP32" # See readme for supported models
sensor_ip: "192.168.1.201" # Lidar Sensor IP
host_ip: "255.255.255.255" # Broadcast IP from Sensor
sensor_model: "VLP32"
sensor_ip: "192.168.1.201"
host_ip: "255.255.255.255"
frame_id: "velodyne"
data_port: 2368 # LiDAR Data Port
gnss_port: 2369 # LiDAR GNSS Port
return_mode: "Dual" # See readme for supported return modes
scan_phase: 0.0 # Angle where scans begin (degrees, [0.,360.]
packet_mtu_size: 1500 # Packet MTU size
rotation_speed: 600 # Motor RPM, the sensor's internal spin rate.
cloud_min_angle: 0 # Field of View, start degrees.
cloud_max_angle: 359 # Field of View, end degrees.
diag_span: 1000 # milliseconds
advanced_diagnostics: False # original diag
min_range: 0.3
max_range: 300.0
view_width: 360.0
calibration_file: "./install/nebula_decoders/share/nebula_decoders/calibration/velodyne/VLP32.yaml"
data_port: 2368
gnss_port: 2369
setup_sensor: True

online: True
1 change: 1 addition & 0 deletions nebula_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
<author>Tier IV</author>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>ros_environment</buildtool_depend>

<depend>diagnostic_msgs</depend>
<depend>diagnostic_updater</depend>
Expand Down
5 changes: 5 additions & 0 deletions nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@ VelodyneDriverRosWrapper::VelodyneDriverRosWrapper(const rclcpp::NodeOptions & o
void VelodyneDriverRosWrapper::ReceiveScanMsgCallback(
const velodyne_msgs::msg::VelodyneScan::SharedPtr scan_msg)
{
auto t_start = std::chrono::high_resolution_clock::now();

// take packets out of scan msg
std::vector<velodyne_msgs::msg::VelodynePacket> pkt_msgs = scan_msg->packets;

Expand Down Expand Up @@ -85,6 +87,9 @@ void VelodyneDriverRosWrapper::ReceiveScanMsgCallback(
rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count());
PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_);
}

auto runtime = std::chrono::high_resolution_clock::now() - t_start;
RCLCPP_DEBUG(get_logger(), "PROFILING {'d_total': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size());
}

void VelodyneDriverRosWrapper::PublishCloud(
Expand Down
6 changes: 3 additions & 3 deletions nebula_ros/src/velodyne/velodyne_hw_monitor_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,7 +266,7 @@ Status VelodyneHwMonitorRosWrapper::GetParameters(
descriptor.dynamic_typing = false;
descriptor.additional_constraints = "";
rcl_interfaces::msg::IntegerRange range;
range.set__from_value(0).set__to_value(359).set__step(1);
range.set__from_value(0).set__to_value(360).set__step(1);
descriptor.integer_range = {range};
this->declare_parameter<uint16_t>("cloud_min_angle", 0, descriptor);
sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int();
Expand All @@ -278,9 +278,9 @@ Status VelodyneHwMonitorRosWrapper::GetParameters(
descriptor.dynamic_typing = false;
descriptor.additional_constraints = "";
rcl_interfaces::msg::IntegerRange range;
range.set__from_value(0).set__to_value(359).set__step(1);
range.set__from_value(0).set__to_value(360).set__step(1);
descriptor.integer_range = {range};
this->declare_parameter<uint16_t>("cloud_max_angle", 359, descriptor);
this->declare_parameter<uint16_t>("cloud_max_angle", 360, descriptor);
sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int();
}

Expand Down
1 change: 1 addition & 0 deletions nebula_tests/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
<author>Tier IV</author>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>ros_environment</buildtool_depend>

<depend>diagnostic_msgs</depend>
<depend>diagnostic_updater</depend>
Expand Down

0 comments on commit 45df6b6

Please sign in to comment.