Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

chore(hesai,velodyne): combine connection-related parameters into connection_mode #211

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
36 changes: 36 additions & 0 deletions nebula_common/include/nebula_common/nebula_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#include <algorithm>
#include <ostream>
#include <stdexcept>
#include <string>
#include <vector>

Expand Down Expand Up @@ -344,6 +345,41 @@
CONTINENTAL_SRR520
};

enum class ConnectionMode {
/// No network connection, listen to replayed packets on a ROS 2 topic
OFFLINE,
/// Passive mode where Nebula does not inquire any settings or diagnostics, only listens via UDP
UDP_ONLY,
/// Nebula compares settings with the sensor and runs all other functionality, but does not modify
/// sensor settings
SKIP_SETUP,
/// All supported network functionality is enabled
FULL
};

inline std::ostream & operator<<(std::ostream & os, ConnectionMode const & arg)
{
switch (arg) {
case ConnectionMode::OFFLINE:
return os << "offline";
case ConnectionMode::UDP_ONLY:
return os << "UDP only";
case ConnectionMode::SKIP_SETUP:
return os << "skip setup";
case ConnectionMode::FULL:
return os << "full";
}
}

inline ConnectionMode connection_mode_from_string(const std::string & str)
{
if (str == "offline") return ConnectionMode::OFFLINE;

Check warning on line 376 in nebula_common/include/nebula_common/nebula_common.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/nebula_common.hpp#L376

Added line #L376 was not covered by tests
if (str == "udp_only") return ConnectionMode::UDP_ONLY;
if (str == "skip_setup") return ConnectionMode::SKIP_SETUP;
if (str == "full") return ConnectionMode::FULL;
throw std::runtime_error("Unknown connection mode " + str);

Check warning on line 380 in nebula_common/include/nebula_common/nebula_common.hpp

View check run for this annotation

Codecov / codecov/patch

nebula_common/include/nebula_common/nebula_common.hpp#L380

Added line #L380 was not covered by tests
}

/// @brief not used?
enum class datatype {
INT8 = 1,
Expand Down
4 changes: 1 addition & 3 deletions nebula_ros/config/lidar/hesai/Pandar128E4X.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@
data_port: 2368
gnss_port: 10110
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
connection_mode: full
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
4 changes: 1 addition & 3 deletions nebula_ros/config/lidar/hesai/Pandar40P.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@
data_port: 2368
gnss_port: 10110
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
connection_mode: full
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
4 changes: 1 addition & 3 deletions nebula_ros/config/lidar/hesai/Pandar64.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@
data_port: 2368
gnss_port: 10110
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
connection_mode: full
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
4 changes: 1 addition & 3 deletions nebula_ros/config/lidar/hesai/PandarAT128.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@
data_port: 2368
gnss_port: 10110
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
connection_mode: full
frame_id: hesai
diag_span: 1000
correction_file: $(find-pkg-share nebula_decoders)/calibration/hesai/$(var sensor_model).dat
Expand Down
4 changes: 1 addition & 3 deletions nebula_ros/config/lidar/hesai/PandarQT128.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@
data_port: 2368
gnss_port: 10110
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
connection_mode: full
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
4 changes: 1 addition & 3 deletions nebula_ros/config/lidar/hesai/PandarQT64.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@
data_port: 2368
gnss_port: 10110
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
connection_mode: full
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
4 changes: 1 addition & 3 deletions nebula_ros/config/lidar/hesai/PandarXT32.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@
data_port: 2368
gnss_port: 10110
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
connection_mode: full
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
4 changes: 1 addition & 3 deletions nebula_ros/config/lidar/hesai/PandarXT32M.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@
data_port: 2368
gnss_port: 10110
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
connection_mode: full
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/config/lidar/robosense/Bpearl.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
data_port: 2368
gnss_port: 2369
packet_mtu_size: 1500
launch_hw: true
connection_mode: full
setup_sensor: true
frame_id: robosense
diag_span: 1000
Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/config/lidar/robosense/Helios.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
data_port: 2368
gnss_port: 2369
packet_mtu_size: 1500
launch_hw: true
connection_mode: full
setup_sensor: true
frame_id: robosense
diag_span: 1000
Expand Down
4 changes: 1 addition & 3 deletions nebula_ros/config/lidar/velodyne/VLP16.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,7 @@
data_port: 2368
gnss_port: 2369
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
connection_mode: full
frame_id: velodyne
advanced_diagnostics: false
diag_span: 1000
Expand Down
4 changes: 1 addition & 3 deletions nebula_ros/config/lidar/velodyne/VLP32.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,7 @@
data_port: 2368
gnss_port: 2369
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
connection_mode: full
frame_id: velodyne
advanced_diagnostics: false
diag_span: 1000
Expand Down
4 changes: 1 addition & 3 deletions nebula_ros/config/lidar/velodyne/VLS128.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,7 @@
data_port: 2368
gnss_port: 2369
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
udp_only: false
connection_mode: full
frame_id: velodyne
advanced_diagnostics: false
diag_span: 1000
Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/config/radar/continental/ARS548.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
frame_id: continental
base_frame: base_link
object_frame: base_link
launch_hw: true
connection_mode: full
multicast_ip: 224.0.2.2
sensor_model: ARS548
configuration_host_port: 42401
Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/config/radar/continental/SRR520.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
frame_id: continental
base_frame: base_link
interface: can4
launch_hw: true
connection_mode: full
receiver_timeout_sec: 0.03
sender_timeout_sec: 0.01
filters: 0:0 # candump-like filters
Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ class HesaiRosWrapper final : public rclcpp::Node

rclcpp::Subscription<pandar_msgs::msg::PandarScan>::SharedPtr packets_sub_{};

bool launch_hw_;
drivers::ConnectionMode connection_mode_;

std::optional<HesaiHwInterfaceWrapper> hw_interface_wrapper_;
std::optional<HesaiHwMonitorWrapper> hw_monitor_wrapper_;
Expand Down
6 changes: 3 additions & 3 deletions nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#pragma once

#include <nebula_common/hesai/hesai_common.hpp>
#include <nebula_common/nebula_common.hpp>
#include <nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp>
#include <rclcpp/rclcpp.hpp>

Expand All @@ -28,7 +29,7 @@ class HesaiHwInterfaceWrapper
HesaiHwInterfaceWrapper(
rclcpp::Node * const parent_node,
std::shared_ptr<const nebula::drivers::HesaiSensorConfiguration> & config,
bool use_udp_only = false);
drivers::ConnectionMode connection_mode);

void on_config_change(
const std::shared_ptr<const nebula::drivers::HesaiSensorConfiguration> & new_config);
Expand All @@ -41,7 +42,6 @@ class HesaiHwInterfaceWrapper
std::shared_ptr<drivers::HesaiHwInterface> hw_interface_;
rclcpp::Logger logger_;
nebula::Status status_;
bool setup_sensor_;
bool use_udp_only_;
drivers::ConnectionMode connection_mode_;
};
} // namespace nebula::ros
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include "nebula_ros/common/parameter_descriptors.hpp"

#include <nebula_common/nebula_common.hpp>
#include <nebula_common/velodyne/velodyne_common.hpp>
#include <nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp>
#include <rclcpp/rclcpp.hpp>
Expand All @@ -30,7 +31,7 @@ class VelodyneHwInterfaceWrapper
VelodyneHwInterfaceWrapper(
rclcpp::Node * const parent_node,
std::shared_ptr<const nebula::drivers::VelodyneSensorConfiguration> & config,
bool use_udp_only = false);
drivers::ConnectionMode connection_mode);

void on_config_change(
const std::shared_ptr<const nebula::drivers::VelodyneSensorConfiguration> & new_config);
Expand All @@ -43,7 +44,6 @@ class VelodyneHwInterfaceWrapper
std::shared_ptr<drivers::VelodyneHwInterface> hw_interface_;
rclcpp::Logger logger_;
nebula::Status status_;
bool setup_sensor_;
bool use_udp_only_;
drivers::ConnectionMode connection_mode_;
};
} // namespace nebula::ros
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ class VelodyneRosWrapper final : public rclcpp::Node

rclcpp::Subscription<velodyne_msgs::msg::VelodyneScan>::SharedPtr packets_sub_{};

bool launch_hw_;
drivers::ConnectionMode connection_mode_;

std::optional<VelodyneHwInterfaceWrapper> hw_interface_wrapper_;
std::optional<VelodyneHwMonitorWrapper> hw_monitor_wrapper_;
Expand Down
14 changes: 3 additions & 11 deletions nebula_ros/schema/Pandar128E4X.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,8 @@
"packet_mtu_size": {
"$ref": "sub/communication.json#/definitions/packet_mtu_size"
},
"launch_hw": {
"$ref": "sub/hardware.json#/definitions/launch_hw"
},
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
"connection_mode": {
"$ref": "sub/hardware.json#/definitions/connection_mode"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
Expand Down Expand Up @@ -110,9 +104,7 @@
"data_port",
"gnss_port",
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"connection_mode",
"frame_id",
"diag_span",
"cloud_min_angle",
Expand Down
14 changes: 3 additions & 11 deletions nebula_ros/schema/Pandar40P.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,8 @@
"packet_mtu_size": {
"$ref": "sub/communication.json#/definitions/packet_mtu_size"
},
"launch_hw": {
"$ref": "sub/hardware.json#/definitions/launch_hw"
},
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
"connection_mode": {
"$ref": "sub/hardware.json#/definitions/connection_mode"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
Expand Down Expand Up @@ -101,9 +95,7 @@
"data_port",
"gnss_port",
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"connection_mode",
"frame_id",
"diag_span",
"cloud_min_angle",
Expand Down
14 changes: 3 additions & 11 deletions nebula_ros/schema/Pandar64.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,8 @@
"packet_mtu_size": {
"$ref": "sub/communication.json#/definitions/packet_mtu_size"
},
"launch_hw": {
"$ref": "sub/hardware.json#/definitions/launch_hw"
},
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
"connection_mode": {
"$ref": "sub/hardware.json#/definitions/connection_mode"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
Expand Down Expand Up @@ -98,9 +92,7 @@
"data_port",
"gnss_port",
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"connection_mode",
"frame_id",
"diag_span",
"cloud_min_angle",
Expand Down
14 changes: 3 additions & 11 deletions nebula_ros/schema/PandarAT128.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,8 @@
"packet_mtu_size": {
"$ref": "sub/communication.json#/definitions/packet_mtu_size"
},
"launch_hw": {
"$ref": "sub/hardware.json#/definitions/launch_hw"
},
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
"connection_mode": {
"$ref": "sub/hardware.json#/definitions/connection_mode"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
Expand Down Expand Up @@ -121,9 +115,7 @@
"data_port",
"gnss_port",
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"connection_mode",
"frame_id",
"diag_span",
"correction_file",
Expand Down
Loading
Loading