Skip to content

Commit

Permalink
Merge branch 'main' into hesai-at128-performance-tuning
Browse files Browse the repository at this point in the history
  • Loading branch information
amc-nu authored Aug 8, 2023
2 parents d7a78b7 + cb25896 commit e591f46
Show file tree
Hide file tree
Showing 10 changed files with 21 additions and 23 deletions.
2 changes: 1 addition & 1 deletion build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,4 @@ repositories:
transport_drivers:
type: git
url: https://github.com/MapIV/transport_drivers
version: tcp
version: boost
4 changes: 2 additions & 2 deletions nebula_common/src/nebula_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,9 +58,9 @@ pcl::PointCloud<PointXYZIRADT>::Ptr convertPointXYZIRCAEDTToPointXYZIRADT(
point.z = p.z;
point.intensity = p.intensity;
point.ring = p.channel;
point.azimuth = rad2deg(p.azimuth);
point.azimuth = rad2deg(p.azimuth) * 100.0;
point.distance = p.distance;
point.time_stamp = static_cast<double>(stamp) + p.time_stamp*10e-9;
point.time_stamp = stamp + static_cast<double>(p.time_stamp)*1e-9;
output_pointcloud->points.emplace_back(point);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

#include "nebula_common/nebula_common.hpp"
#include "nebula_common/nebula_status.hpp"
#include "udp_driver/udp_driver.hpp"
#include "boost_udp_driver/udp_driver.hpp"

#include <stdexcept>
#include <string>
Expand All @@ -20,7 +20,7 @@ class NebulaHwInterfaceBase
/**
* Callback function to receive the Cloud Packet data from the UDP Driver
* @param buffer Buffer containing the data received from the UDP socket
* @return Status::OK if no error occured.
* @return Status::OK if no error occurred.
*/
virtual void ReceiveCloudPacketCallback(const std::vector<uint8_t> & buffer) = 0;
// virtual Status RegisterScanCallback(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@
#include "nebula_common/hesai/hesai_status.hpp"
#include "nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp"
#include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp"
#include "tcp_driver/http_client_driver.hpp"
#include "tcp_driver/tcp_driver.hpp"
#include "udp_driver/udp_driver.hpp"
#include "boost_tcp_driver/http_client_driver.hpp"
#include "boost_tcp_driver/tcp_driver.hpp"
#include "boost_udp_driver/udp_driver.hpp"

#include <rclcpp/rclcpp.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
#include "nebula_common/velodyne/velodyne_common.hpp"
#include "nebula_common/velodyne/velodyne_status.hpp"
#include "nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp"
#include "tcp_driver/http_client_driver.hpp"
#include "udp_driver/udp_driver.hpp"
#include "boost_tcp_driver/http_client_driver.hpp"
#include "boost_udp_driver/udp_driver.hpp"

#include <rclcpp/rclcpp.hpp>

Expand Down
4 changes: 2 additions & 2 deletions nebula_hw_interfaces/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
<depend>pandar_msgs</depend>
<depend>rclcpp</depend>
<depend>sensor_msgs</depend>
<depend>tcp_driver</depend>
<depend>udp_driver</depend>
<depend>boost_tcp_driver</depend>
<depend>boost_udp_driver</depend>
<depend>velodyne_msgs</depend>

<test_depend>ament_cmake_gtest</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include "nebula_common/nebula_common.hpp"
#include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp"
#include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp"
#include "tcp_driver/tcp_driver.hpp"
#include "boost_tcp_driver/tcp_driver.hpp"

#include <ament_index_cpp/get_package_prefix.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include "nebula_common/nebula_common.hpp"
#include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp"
#include "nebula_ros/common/nebula_hw_monitor_ros_wrapper_base.hpp"
#include "tcp_driver/tcp_driver.hpp"
#include "boost_tcp_driver/tcp_driver.hpp"

#include <ament_index_cpp/get_package_prefix.hpp>
#include <diagnostic_updater/diagnostic_updater.hpp>
Expand All @@ -15,6 +15,11 @@
#include <boost/asio.hpp>

#include <mutex>
#include <boost/algorithm/string/join.hpp>
#include <boost/asio.hpp>
#include <boost/lexical_cast.hpp>

#include <thread>

namespace nebula
{
Expand Down
8 changes: 0 additions & 8 deletions nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp
Original file line number Diff line number Diff line change
@@ -1,13 +1,5 @@
#include "nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp"

#include "tcp_driver/tcp_driver.hpp"

#include <boost/algorithm/string/join.hpp>
#include <boost/asio.hpp>
#include <boost/lexical_cast.hpp>

#include <thread>

namespace nebula
{
namespace ros
Expand Down
3 changes: 2 additions & 1 deletion nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ void VelodyneDriverRosWrapper::ReceiveScanMsgCallback(
std::tuple<nebula::drivers::NebulaPointCloudPtr, double> pointcloud_ts =
driver_ptr_->ConvertScanToPointcloud(scan_msg);
nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts);
double cloud_stamp = std::get<1>(pointcloud_ts);
if (pointcloud == nullptr) {
RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed.");
return;
Expand Down Expand Up @@ -77,7 +78,7 @@ void VelodyneDriverRosWrapper::ReceiveScanMsgCallback(
aw_points_ex_pub_->get_subscription_count() > 0 ||
aw_points_ex_pub_->get_intra_process_subscription_count() > 0) {
const auto autoware_ex_cloud =
nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, 0.0);//velodyne drivers originally doesn't use absolute time
nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, cloud_stamp);
auto ros_pc_msg_ptr = std::make_unique<sensor_msgs::msg::PointCloud2>();
pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr);
ros_pc_msg_ptr->header.stamp =
Expand Down

0 comments on commit e591f46

Please sign in to comment.