Skip to content

Commit

Permalink
Merge branch tier4:develop into launch-hw-launch-argument
Browse files Browse the repository at this point in the history
  • Loading branch information
mojomex committed Sep 6, 2024
2 parents 6b8d67c + 7b429cb commit 5dbecd3
Show file tree
Hide file tree
Showing 7 changed files with 46 additions and 5 deletions.
2 changes: 1 addition & 1 deletion build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ repositories:
transport_drivers:
type: git
url: https://github.com/mojomex/transport_drivers
version: mutable-buffer-in-udp-callback
version: feat-set-rmem
# Continental compatible version of ROS 2 socket CAN
ros2_socketcan:
type: git
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
// boost/property_tree/ in some versions of boost.
// See: https://github.com/boostorg/property_tree/issues/51
#include <boost/version.hpp>

#include <cstddef>
#if (BOOST_VERSION / 100 >= 1073 && BOOST_VERSION / 100 <= 1076) // Boost 1.73 - 1.76
#define BOOST_BIND_GLOBAL_PLACEHOLDERS
#endif
Expand Down Expand Up @@ -103,6 +105,12 @@ const uint16_t PANDAR128_E4X_PACKET_SIZE = 861;
const uint16_t PANDAR128_E4X_EXTENDED_PACKET_SIZE = 1117;
const uint16_t MTU_SIZE = 1500;

/// @brief The kernel buffer size in bytes to use for receiving UDP packets. If the buffer is too
/// small to bridge scheduling and processing delays, packets will be dropped. This corresponds to
/// the net.core.rmem_default setting in Linux. The current value is hardcoded to accommodate one
/// pointcloud worth of OT128 packets (currently the highest data rate sensor supported).
const size_t UDP_SOCKET_BUFFER_SIZE = MTU_SIZE * 3600;

// Time interval between Announce messages, in units of log seconds (default: 1)
const int PTP_LOG_ANNOUNCE_INTERVAL = 1;
// Time interval between Sync messages, in units of log seconds (default: 1)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,12 @@

#include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp"

#include "nebula_common/nebula_status.hpp"

#include <boost/asio/socket_base.hpp>

#include <sstream>
#include <string>

// #define WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE

Expand Down Expand Up @@ -153,6 +158,15 @@ Status HesaiHwInterface::SensorInterfaceStart()
#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE
PrintError("open ok");
#endif

bool success = cloud_udp_driver_->receiver()->setKernelBufferSize(UDP_SOCKET_BUFFER_SIZE);
if (!success) {
PrintError(
"Could not set receive buffer size. Try increasing net.core.rmem_max to " +
std::to_string(UDP_SOCKET_BUFFER_SIZE) + " B.");
return Status::ERROR_1;
}

cloud_udp_driver_->receiver()->bind();
#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE
PrintError("bind ok");
Expand Down
5 changes: 4 additions & 1 deletion nebula_ros/launch/continental_launch_all_hw.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
<?xml version="1.0"?>
<launch>
<arg name="sensor_model" default="ARS548"/>
<arg name="sensor_model">
<choice value="ARS548" />
<choice value="SRR520" />
</arg>
<arg name="launch_hw" default="true" description="Whether to connect to a real sensor (true) or to accept packet messages (false).">
<choice value="true" />
<choice value="false" />
Expand Down
11 changes: 10 additions & 1 deletion nebula_ros/launch/hesai_launch_all_hw.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,15 @@
<?xml version="1.0"?>
<launch>
<arg name="sensor_model" description="Pandar64|Pandar40P|PandarXT32|PandarXT32M|PandarAT128|PandarQT64|PandarQT128|Pandar128E4X"/>
<arg name="sensor_model">
<choice value="Pandar40P" />
<choice value="Pandar64" />
<choice value="Pandar128E4X" />
<choice value="PandarAT128" />
<choice value="PandarQT64" />
<choice value="PandarQT128" />
<choice value="PandarXT32" />
<choice value="PandarXT32M" />
</arg>
<arg name="launch_hw" default="true" description="Whether to connect to a real sensor (true) or to accept packet messages (false).">
<choice value="true" />
<choice value="false" />
Expand Down
5 changes: 4 additions & 1 deletion nebula_ros/launch/robosense_launch_all_hw.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
<?xml version="1.0"?>
<launch>
<arg name="sensor_model" description="Helios|Bpearl"/>
<arg name="sensor_model">
<choice value="Helios" />
<choice value="Bpearl" />
</arg>
<arg name="launch_hw" default="true" description="Whether to connect to a real sensor (true) or to accept packet messages (false).">
<choice value="true" />
<choice value="false" />
Expand Down
6 changes: 5 additions & 1 deletion nebula_ros/launch/velodyne_launch_all_hw.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,10 @@
<?xml version="1.0"?>
<launch>
<arg name="sensor_model" description="VLP16|VLP32|VLS128"/>
<arg name="sensor_model">
<choice value="VLP16" />
<choice value="VLP32" />
<choice value="VLS128" />
</arg>
<arg name="launch_hw" default="true" description="Whether to connect to a real sensor (true) or to accept packet messages (false).">
<choice value="true" />
<choice value="false" />
Expand Down

0 comments on commit 5dbecd3

Please sign in to comment.