diff --git a/README.md b/README.md
index a79fe2573..fe5e4aa79 100644
--- a/README.md
+++ b/README.md
@@ -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.
diff --git a/nebula_common/package.xml b/nebula_common/package.xml
index 5eff4521d..d769e273e 100644
--- a/nebula_common/package.xml
+++ b/nebula_common/package.xml
@@ -10,6 +10,7 @@
Tier IV
ament_cmake_auto
+ ros_environment
libpcl-all-dev
pcl_conversions
diff --git a/nebula_decoders/package.xml b/nebula_decoders/package.xml
index cac32c92b..c5463e5eb 100644
--- a/nebula_decoders/package.xml
+++ b/nebula_decoders/package.xml
@@ -10,6 +10,7 @@
Tier IV
ament_cmake_auto
+ ros_environment
angles
libpcl-all-dev
diff --git a/nebula_examples/package.xml b/nebula_examples/package.xml
index f6bd71e9a..ab6d61eb7 100644
--- a/nebula_examples/package.xml
+++ b/nebula_examples/package.xml
@@ -10,6 +10,7 @@
Tier IV
ament_cmake_auto
+ ros_environment
diagnostic_msgs
diagnostic_updater
diff --git a/nebula_messages/pandar_msgs/package.xml b/nebula_messages/pandar_msgs/package.xml
index b8fac6315..071ab79bc 100644
--- a/nebula_messages/pandar_msgs/package.xml
+++ b/nebula_messages/pandar_msgs/package.xml
@@ -3,13 +3,13 @@
pandar_msgs
0.0.0
- 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.
hirakawa
Apache 2
- ament_cmake
+ ament_cmake_auto
rosidl_default_generators
builtin_interfaces
diff --git a/nebula_messages/velodyne_msgs/package.xml b/nebula_messages/velodyne_msgs/package.xml
index 0c5125943..942e4753b 100644
--- a/nebula_messages/velodyne_msgs/package.xml
+++ b/nebula_messages/velodyne_msgs/package.xml
@@ -6,7 +6,7 @@
Perception Engine
BSD
- ament_cmake
+ ament_cmake_auto
rosidl_default_generators
std_msgs
diff --git a/nebula_ros/package.xml b/nebula_ros/package.xml
index 334d45672..3a9f2ecca 100644
--- a/nebula_ros/package.xml
+++ b/nebula_ros/package.xml
@@ -10,6 +10,7 @@
Tier IV
ament_cmake_auto
+ ros_environment
diagnostic_msgs
diagnostic_updater
diff --git a/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp b/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp
index 56a54be34..e41469aac 100644
--- a/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp
+++ b/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp
@@ -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 pkt_msgs = scan_msg->packets;
@@ -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(
diff --git a/nebula_tests/package.xml b/nebula_tests/package.xml
index 91cb322e2..4b79ad749 100644
--- a/nebula_tests/package.xml
+++ b/nebula_tests/package.xml
@@ -10,6 +10,7 @@
Tier IV
ament_cmake_auto
+ ros_environment
diagnostic_msgs
diagnostic_updater