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

feat: allow to launch hardware in listen mode #210

Merged
merged 9 commits into from
Oct 25, 2024
54 changes: 28 additions & 26 deletions docs/parameters.md
Original file line number Diff line number Diff line change
Expand Up @@ -60,21 +60,22 @@ Parameters shared by all supported models:

### Hardware interface parameters

| Parameter | Type | Default | Accepted values | Description |
| ------------------------------ | ------ | --------------- | ----------------- | ------------------------------ |
| frame_id | string | hesai | | ROS frame ID |
| sensor_ip | string | 192.168.1.201 | | Sensor IP |
| host_ip | string | 255.255.255.255 | | Host IP |
| data_port | uint16 | 2368 | | Sensor port |
| gnss_port | uint16 | 2369 | | GNSS port |
| frequency_ms | uint16 | 100 | milliseconds, > 0 | Time per scan |
| packet_mtu_size | uint16 | 1500 | | Packet MTU size |
| rotation_speed | uint16 | 600 | | Rotation speed |
| cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle |
| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle |
| dual_return_distance_threshold | double | 0.1 | | Dual return distance threshold |
| diag_span | uint16 | 1000 | milliseconds, > 0 | Diagnostic span |
| setup_sensor | bool | True | True, False | Configure sensor settings |
| Parameter | Type | Default | Accepted values | Description |
| ------------------------------ | ------ | --------------- | ----------------- | ------------------------------------------------------------ |
| frame_id | string | hesai | | ROS frame ID |
| sensor_ip | string | 192.168.1.201 | | Sensor IP |
| host_ip | string | 255.255.255.255 | | Host IP |
| data_port | uint16 | 2368 | | Sensor port |
| gnss_port | uint16 | 2369 | | GNSS port |
| frequency_ms | uint16 | 100 | milliseconds, > 0 | Time per scan |
| packet_mtu_size | uint16 | 1500 | | Packet MTU size |
| rotation_speed | uint16 | 600 | | Rotation speed |
| cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle |
| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle |
| dual_return_distance_threshold | double | 0.1 | | Dual return distance threshold |
| diag_span | uint16 | 1000 | milliseconds, > 0 | Diagnostic span |
| setup_sensor | bool | True | True, False | Configure sensor settings |
| communicate_with_sensor | bool | True | True, False | Enable communication with sensor (listen mode only if false) |

### Driver parameters

Expand All @@ -97,17 +98,18 @@ Parameters shared by all supported models:

### Hardware interface parameters

| Parameter | Type | Default | Accepted values | Description |
| --------------- | ------ | --------------- | ----------------- | --------------- |
| frame_id | string | velodyne | | ROS frame ID |
| sensor_ip | string | 192.168.1.201 | | Sensor IP |
| host_ip | string | 255.255.255.255 | | Host IP |
| data_port | uint16 | 2368 | | Sensor port |
| gnss_port | uint16 | 2369 | | GNSS port |
| frequency_ms | uint16 | 100 | milliseconds, > 0 | Time per scan |
| packet_mtu_size | uint16 | 1500 | | Packet MTU size |
| cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle |
| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle |
| Parameter | Type | Default | Accepted values | Description |
| ----------------------- | ------ | --------------- | ----------------- | ------------------------------------------------------------ |
| frame_id | string | velodyne | | ROS frame ID |
| sensor_ip | string | 192.168.1.201 | | Sensor IP |
| host_ip | string | 255.255.255.255 | | Host IP |
| data_port | uint16 | 2368 | | Sensor port |
| gnss_port | uint16 | 2369 | | GNSS port |
| frequency_ms | uint16 | 100 | milliseconds, > 0 | Time per scan |
| packet_mtu_size | uint16 | 1500 | | Packet MTU size |
| cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle |
| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle |
| communicate_with_sensor | bool | True | True, False | Enable communication with sensor (listen mode only if false) |

### Driver parameters

Expand Down
1 change: 1 addition & 0 deletions nebula_ros/config/lidar/hesai/Pandar128E4X.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
communicate_with_sensor: true
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
1 change: 1 addition & 0 deletions nebula_ros/config/lidar/hesai/Pandar40P.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
communicate_with_sensor: true
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
1 change: 1 addition & 0 deletions nebula_ros/config/lidar/hesai/Pandar64.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
communicate_with_sensor: true
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
1 change: 1 addition & 0 deletions nebula_ros/config/lidar/hesai/PandarAT128.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
communicate_with_sensor: true
frame_id: hesai
diag_span: 1000
correction_file: $(find-pkg-share nebula_decoders)/calibration/hesai/$(var sensor_model).dat
Expand Down
1 change: 1 addition & 0 deletions nebula_ros/config/lidar/hesai/PandarQT128.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
communicate_with_sensor: true
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
1 change: 1 addition & 0 deletions nebula_ros/config/lidar/hesai/PandarQT64.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
communicate_with_sensor: true
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
1 change: 1 addition & 0 deletions nebula_ros/config/lidar/hesai/PandarXT32.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
communicate_with_sensor: true
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
1 change: 1 addition & 0 deletions nebula_ros/config/lidar/hesai/PandarXT32M.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
communicate_with_sensor: true
frame_id: hesai
diag_span: 1000
min_range: 0.3
Expand Down
1 change: 1 addition & 0 deletions nebula_ros/config/lidar/velodyne/VLP16.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
communicate_with_sensor: true
frame_id: velodyne
advanced_diagnostics: false
diag_span: 1000
Expand Down
1 change: 1 addition & 0 deletions nebula_ros/config/lidar/velodyne/VLP32.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
communicate_with_sensor: true
frame_id: velodyne
advanced_diagnostics: false
diag_span: 1000
Expand Down
1 change: 1 addition & 0 deletions nebula_ros/config/lidar/velodyne/VLS128.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
packet_mtu_size: 1500
launch_hw: true
setup_sensor: true
communicate_with_sensor: true
frame_id: velodyne
advanced_diagnostics: false
diag_span: 1000
Expand Down
4 changes: 3 additions & 1 deletion nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,8 @@ class HesaiHwInterfaceWrapper
public:
HesaiHwInterfaceWrapper(
rclcpp::Node * const parent_node,
std::shared_ptr<const nebula::drivers::HesaiSensorConfiguration> & config);
std::shared_ptr<const nebula::drivers::HesaiSensorConfiguration> & config,
bool communicate_with_sensor = true);

void on_config_change(
const std::shared_ptr<const nebula::drivers::HesaiSensorConfiguration> & new_config);
Expand All @@ -41,5 +42,6 @@ class HesaiHwInterfaceWrapper
rclcpp::Logger logger_;
nebula::Status status_;
bool setup_sensor_;
bool communicate_with_sensor_;
};
} // namespace nebula::ros
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,8 @@ class VelodyneHwInterfaceWrapper
public:
VelodyneHwInterfaceWrapper(
rclcpp::Node * const parent_node,
std::shared_ptr<const nebula::drivers::VelodyneSensorConfiguration> & config);
std::shared_ptr<const nebula::drivers::VelodyneSensorConfiguration> & config,
bool communicate_with_sensor = true);

void on_config_change(
const std::shared_ptr<const nebula::drivers::VelodyneSensorConfiguration> & new_config);
Expand All @@ -43,5 +44,6 @@ class VelodyneHwInterfaceWrapper
rclcpp::Logger logger_;
nebula::Status status_;
bool setup_sensor_;
bool communicate_with_sensor_;
};
} // namespace nebula::ros
14 changes: 10 additions & 4 deletions nebula_ros/src/hesai/hesai_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,20 +40,26 @@
RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *sensor_cfg_ptr_);

launch_hw_ = declare_parameter<bool>("launch_hw", param_read_only());
bool communicate_with_sensor =
declare_parameter<bool>("communicate_with_sensor", param_read_only());

Check warning on line 44 in nebula_ros/src/hesai/hesai_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/hesai/hesai_ros_wrapper.cpp#L44

Added line #L44 was not covered by tests

if (launch_hw_) {
hw_interface_wrapper_.emplace(this, sensor_cfg_ptr_);
hw_monitor_wrapper_.emplace(this, hw_interface_wrapper_->hw_interface(), sensor_cfg_ptr_);
hw_interface_wrapper_.emplace(this, sensor_cfg_ptr_, communicate_with_sensor);

Check warning on line 47 in nebula_ros/src/hesai/hesai_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/hesai/hesai_ros_wrapper.cpp#L47

Added line #L47 was not covered by tests
if (communicate_with_sensor) { // hardware monitor requires communication with sensor
hw_monitor_wrapper_.emplace(this, hw_interface_wrapper_->hw_interface(), sensor_cfg_ptr_);

Check warning on line 49 in nebula_ros/src/hesai/hesai_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/hesai/hesai_ros_wrapper.cpp#L49

Added line #L49 was not covered by tests
}
}

auto calibration_result = get_calibration_data(sensor_cfg_ptr_->calibration_path);
bool force_load_caibration_from_file = !communicate_with_sensor;

Check warning on line 53 in nebula_ros/src/hesai/hesai_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/hesai/hesai_ros_wrapper.cpp#L53

Added line #L53 was not covered by tests
auto calibration_result =
get_calibration_data(sensor_cfg_ptr_->calibration_path, force_load_caibration_from_file);

Check warning on line 55 in nebula_ros/src/hesai/hesai_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/hesai/hesai_ros_wrapper.cpp#L55

Added line #L55 was not covered by tests
if (!calibration_result.has_value()) {
throw std::runtime_error(
(std::stringstream() << "No valid calibration found: " << calibration_result.error()).str());
}

if (
hw_interface_wrapper_ &&
hw_interface_wrapper_ && communicate_with_sensor &&

Check warning on line 62 in nebula_ros/src/hesai/hesai_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/hesai/hesai_ros_wrapper.cpp#L62

Added line #L62 was not covered by tests
sensor_cfg_ptr_->sensor_model != drivers::SensorModel::HESAI_PANDARAT128) {
auto status =
hw_interface_wrapper_->hw_interface()->checkAndSetLidarRange(*calibration_result.value());
Expand Down
13 changes: 10 additions & 3 deletions nebula_ros/src/hesai/hw_interface_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,12 @@

HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(
rclcpp::Node * const parent_node,
std::shared_ptr<const nebula::drivers::HesaiSensorConfiguration> & config)
std::shared_ptr<const nebula::drivers::HesaiSensorConfiguration> & config,
bool communicate_with_sensor)

Check warning on line 13 in nebula_ros/src/hesai/hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/hesai/hw_interface_wrapper.cpp#L13

Added line #L13 was not covered by tests
: hw_interface_(new nebula::drivers::HesaiHwInterface()),
logger_(parent_node->get_logger().get_child("HwInterface")),
status_(Status::NOT_INITIALIZED)
status_(Status::NOT_INITIALIZED),
communicate_with_sensor_(communicate_with_sensor)

Check warning on line 17 in nebula_ros/src/hesai/hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/hesai/hw_interface_wrapper.cpp#L16-L17

Added lines #L16 - L17 were not covered by tests
{
setup_sensor_ = parent_node->declare_parameter<bool>("setup_sensor", param_read_only());
bool retry_connect = parent_node->declare_parameter<bool>("retry_hw", param_read_only());
Expand All @@ -28,6 +30,11 @@
hw_interface_->SetLogger(std::make_shared<rclcpp::Logger>(parent_node->get_logger()));
hw_interface_->SetTargetModel(config->sensor_model);

if (!communicate_with_sensor_) {
// Do not initialize Tcp if communication is disabled
return;
mojomex marked this conversation as resolved.
Show resolved Hide resolved
}

int retry_count = 0;

while (true) {
Expand Down Expand Up @@ -65,7 +72,7 @@
{
hw_interface_->SetSensorConfiguration(
std::static_pointer_cast<const nebula::drivers::SensorConfigurationBase>(new_config));
if (setup_sensor_) {
if (communicate_with_sensor_ && setup_sensor_) {
hw_interface_->CheckAndSetConfig();
}
}
Expand Down
19 changes: 14 additions & 5 deletions nebula_ros/src/velodyne/hw_interface_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,12 @@

VelodyneHwInterfaceWrapper::VelodyneHwInterfaceWrapper(
rclcpp::Node * const parent_node,
std::shared_ptr<const nebula::drivers::VelodyneSensorConfiguration> & config)
std::shared_ptr<const nebula::drivers::VelodyneSensorConfiguration> & config,
bool communicate_with_sensor)

Check warning on line 11 in nebula_ros/src/velodyne/hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/velodyne/hw_interface_wrapper.cpp#L11

Added line #L11 was not covered by tests
: hw_interface_(new nebula::drivers::VelodyneHwInterface()),
logger_(parent_node->get_logger().get_child("HwInterfaceWrapper")),
status_(Status::NOT_INITIALIZED)
status_(Status::NOT_INITIALIZED),
communicate_with_sensor_(communicate_with_sensor)

Check warning on line 15 in nebula_ros/src/velodyne/hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/velodyne/hw_interface_wrapper.cpp#L14-L15

Added lines #L14 - L15 were not covered by tests
{
setup_sensor_ = parent_node->declare_parameter<bool>("setup_sensor", param_read_only());

Expand All @@ -23,6 +25,11 @@
(std::stringstream{} << "Could not initialize HW interface: " << status_).str());
}

if (!communicate_with_sensor_) {
// Do not initialize http client if communication is disabled
return;
mojomex marked this conversation as resolved.
Show resolved Hide resolved
}

status_ = hw_interface_->init_http_client();

if (status_ != Status::OK) {
Expand All @@ -47,9 +54,11 @@
const std::shared_ptr<const nebula::drivers::VelodyneSensorConfiguration> & new_config)
{
hw_interface_->initialize_sensor_configuration(new_config);
hw_interface_->init_http_client();
if (setup_sensor_) {
hw_interface_->set_sensor_configuration(new_config);
if (communicate_with_sensor_) {
hw_interface_->init_http_client();

Check warning on line 58 in nebula_ros/src/velodyne/hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/velodyne/hw_interface_wrapper.cpp#L58

Added line #L58 was not covered by tests
if (setup_sensor_) {
hw_interface_->set_sensor_configuration(new_config);

Check warning on line 60 in nebula_ros/src/velodyne/hw_interface_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/velodyne/hw_interface_wrapper.cpp#L60

Added line #L60 was not covered by tests
}
}
}

Expand Down
8 changes: 6 additions & 2 deletions nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,14 @@
RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *sensor_cfg_ptr_);

launch_hw_ = declare_parameter<bool>("launch_hw", param_read_only());
bool communicate_with_sensor =
declare_parameter<bool>("communicate_with_sensor", param_read_only());

Check warning on line 31 in nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp#L31

Added line #L31 was not covered by tests

if (launch_hw_) {
hw_interface_wrapper_.emplace(this, sensor_cfg_ptr_);
hw_monitor_wrapper_.emplace(this, hw_interface_wrapper_->hw_interface(), sensor_cfg_ptr_);
hw_interface_wrapper_.emplace(this, sensor_cfg_ptr_, communicate_with_sensor);

Check warning on line 34 in nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp#L34

Added line #L34 was not covered by tests
if (communicate_with_sensor) { // hardware monitor requires communication with sensor
hw_monitor_wrapper_.emplace(this, hw_interface_wrapper_->hw_interface(), sensor_cfg_ptr_);

Check warning on line 36 in nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp#L36

Added line #L36 was not covered by tests
}
}

decoder_wrapper_.emplace(
Expand Down
Loading