Skip to content

Commit

Permalink
reword later
Browse files Browse the repository at this point in the history
  • Loading branch information
mojomex committed Mar 26, 2024
1 parent e984987 commit 1d60f66
Show file tree
Hide file tree
Showing 9 changed files with 363 additions and 361 deletions.
23 changes: 23 additions & 0 deletions nebula_messages/nebula_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
cmake_minimum_required(VERSION 3.14)
project(nebula_msgs)

if (NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_EXTENSIONS OFF)
endif ()

if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif ()

find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

rosidl_generate_interfaces(${PROJECT_NAME}
"msg/RawPacketStamped.msg"
DEPENDENCIES
builtin_interfaces
)

ament_package()
2 changes: 2 additions & 0 deletions nebula_messages/nebula_msgs/msg/RawPacketStamped.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
builtin_interfaces/Time stamp
uint8[] data
23 changes: 23 additions & 0 deletions nebula_messages/nebula_msgs/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version="1.0"?>
<package format="3">
<name>nebula_msgs</name>
<version>0.0.0</version>
<description>
ROS message definitions for timestamped UDP packets.
</description>
<maintainer email="[email protected]">Max Schmeller</maintainer>
<license>Apache 2</license>

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

<depend>builtin_interfaces</depend>

<exec_depend>rosidl_default_runtime</exec_depend>

<member_of_group>rosidl_interface_packages</member_of_group>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
1 change: 1 addition & 0 deletions nebula_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ find_package(nebula_decoders REQUIRED)
find_package(nebula_hw_interfaces REQUIRED)
find_package(yaml-cpp REQUIRED)
find_package(robosense_msgs REQUIRED)
find_package(nebula_msgs REQUIRED)

include_directories(
include
Expand Down
28 changes: 14 additions & 14 deletions nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,7 @@
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>

#include "pandar_msgs/msg/pandar_packet.hpp"
#include "pandar_msgs/msg/pandar_scan.hpp"
#include "nebula_msgs/msg/raw_packet_stamped.hpp"

#include <boost/algorithm/string/join.hpp>
#include <boost/asio.hpp>
Expand Down Expand Up @@ -72,23 +71,21 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase
Status Shutdown() override;

private:
/// @brief Initializing ros wrapper
/// @brief Initialize pointcloud decoder
/// @param sensor_configuration SensorConfiguration for this driver
/// @param calibration_configuration CalibrationConfiguration for this driver
/// @return Resulting status
Status InitializeCloudDriver(
std::shared_ptr<drivers::SensorConfigurationBase> sensor_configuration,
std::shared_ptr<drivers::CalibrationConfigurationBase> calibration_configuration) override;

/// @brief Initializing ros wrapper for AT
/// @param sensor_configuration SensorConfiguration for this driver
/// @param calibration_configuration CalibrationConfiguration for this driver
/// @param correction_configuration CorrectionConfiguration for this driver
/// @param correction_configuration CorrectionConfiguration for this driver (only for AT128, ignored otherwise)
/// @return Resulting status
Status InitializeCloudDriver(
const std::shared_ptr<drivers::SensorConfigurationBase> & sensor_configuration,
const std::shared_ptr<drivers::CalibrationConfigurationBase> & calibration_configuration,
const std::shared_ptr<drivers::HesaiCorrection> & correction_configuration);
const std::shared_ptr<drivers::HesaiCorrection> & correction_configuration = nullptr);

Status InitializeCloudDriver(
std::shared_ptr<drivers::SensorConfigurationBase> sensor_configuration,
std::shared_ptr<drivers::CalibrationConfigurationBase> calibration_configuration) {
return InitializeCloudDriver(sensor_configuration, calibration_configuration, nullptr);
}

/// @brief Get configurations from ros parameters
/// @param sensor_configuration Output of SensorConfiguration
Expand Down Expand Up @@ -188,7 +185,10 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase

std::shared_ptr<drivers::HesaiDriver> driver_ptr_;
Status wrapper_status_;
rclcpp::Subscription<pandar_msgs::msg::PandarScan>::SharedPtr pandar_scan_sub_;

rclcpp::Publisher<nebula_msgs::msg::RawPacketStamped>::SharedPtr packet_pub_;
rclcpp::Subscription<nebula_msgs::msg::RawPacketStamped>::SharedPtr packet_sub_;

rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr nebula_points_pub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr aw_points_ex_pub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr aw_points_base_pub_;
Expand Down
4 changes: 0 additions & 4 deletions nebula_ros/launch/hesai_launch_all_hw.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,6 @@
<arg name="ptp_domain" default="0" description="PTP Domain [0-127]."/>
<arg name="ptp_transport_type" default="UDP" description="1588v2 supports 'UDP' or 'L2', other profiles only L2 (HW)"/>
<arg name="ptp_switch_type" default="TSN" description="For automotive profile,'TSN' or 'NON_TSN'"/>
<arg name="delay_hw_ms" default="1000" description="hw driver startup delay in milliseconds."/>
<arg name="delay_monitor_ms" default="2000" description="hw monitor startup delay in milliseconds."/>
<arg name="retry_hw" default="True" description="hw driver startup retry (false when using pcap)."/>
<arg name="debug_logging" default="False" description="Launches Monitor/HW Interfaces and calibration acquisition"/>

Expand All @@ -55,14 +53,12 @@
<param name="cloud_max_angle" value="$(var cloud_max_angle)"/>
<param name="dual_return_distance_threshold" value="$(var dual_return_distance_threshold)"/>
<param name="setup_sensor" value="$(var setup_sensor)"/>
<param name="delay_hw_ms" value="$(var delay_hw_ms)"/>
<param name="retry_hw" value="$(var retry_hw)"/>
<param name="ptp_profile" value="$(var ptp_profile)"/>
<param name="ptp_domain" value="$(var ptp_domain)"/>
<param name="ptp_transport_type" value="$(var ptp_transport_type)"/>
<param name="ptp_switch_type" value="$(var ptp_switch_type)"/>

<param name="diag_span" value="$(var diag_span)"/>
<param name="delay_monitor_ms" value="$(var delay_monitor_ms)"/>
</node>
</launch>
1 change: 1 addition & 0 deletions nebula_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
<depend>yaml-cpp</depend>
<depend>velodyne_msgs</depend>
<depend>robosense_msgs</depend>
<depend>nebula_msgs</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Loading

0 comments on commit 1d60f66

Please sign in to comment.