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 |
| udp_only | bool | False | True, False | Use UDP protocol only (settings synchronization and diagnostics publishing are disabled) |

### 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 |
| udp_only | bool | False | True, False | Use UDP protocol only (settings synchronization and diagnostics publishing are disabled) |

### 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
udp_only: false
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
udp_only: false
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
udp_only: false
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
udp_only: false
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
udp_only: false
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
udp_only: false
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
udp_only: false
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
udp_only: false
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
udp_only: false
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
udp_only: false
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
udp_only: false
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 use_udp_only = false);

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 use_udp_only_;
};
} // 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 use_udp_only = false);

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 use_udp_only_;
};
} // namespace nebula::ros
4 changes: 4 additions & 0 deletions nebula_ros/schema/Pandar128E4X.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
},
Expand Down Expand Up @@ -109,6 +112,7 @@
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"frame_id",
"diag_span",
"cloud_min_angle",
Expand Down
4 changes: 4 additions & 0 deletions nebula_ros/schema/Pandar40P.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
},
Expand Down Expand Up @@ -100,6 +103,7 @@
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"frame_id",
"diag_span",
"cloud_min_angle",
Expand Down
4 changes: 4 additions & 0 deletions nebula_ros/schema/Pandar64.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
},
Expand Down Expand Up @@ -97,6 +100,7 @@
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"frame_id",
"diag_span",
"cloud_min_angle",
Expand Down
4 changes: 4 additions & 0 deletions nebula_ros/schema/PandarAT128.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
},
Expand Down Expand Up @@ -120,6 +123,7 @@
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"frame_id",
"diag_span",
"correction_file",
Expand Down
4 changes: 4 additions & 0 deletions nebula_ros/schema/PandarQT128.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
},
Expand Down Expand Up @@ -103,6 +106,7 @@
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"frame_id",
"diag_span",
"cloud_min_angle",
Expand Down
4 changes: 4 additions & 0 deletions nebula_ros/schema/PandarQT64.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
},
Expand Down Expand Up @@ -100,6 +103,7 @@
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"frame_id",
"diag_span",
"cloud_min_angle",
Expand Down
4 changes: 4 additions & 0 deletions nebula_ros/schema/PandarXT32.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
},
Expand Down Expand Up @@ -103,6 +106,7 @@
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"frame_id",
"diag_span",
"cloud_min_angle",
Expand Down
4 changes: 4 additions & 0 deletions nebula_ros/schema/PandarXT32M.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
},
Expand Down Expand Up @@ -103,6 +106,7 @@
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"frame_id",
"diag_span",
"cloud_min_angle",
Expand Down
4 changes: 4 additions & 0 deletions nebula_ros/schema/VLP16.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,9 @@
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
},
Expand Down Expand Up @@ -72,6 +75,7 @@
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"frame_id",
"advanced_diagnostics",
"diag_span",
Expand Down
4 changes: 4 additions & 0 deletions nebula_ros/schema/VLP32.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,9 @@
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
},
Expand Down Expand Up @@ -72,6 +75,7 @@
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"frame_id",
"advanced_diagnostics",
"diag_span",
Expand Down
4 changes: 4 additions & 0 deletions nebula_ros/schema/VLS128.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,9 @@
"setup_sensor": {
"$ref": "sub/hardware.json#/definitions/setup_sensor"
},
"udp_only": {
"$ref": "sub/hardware.json#/definitions/udp_only"
},
"frame_id": {
"$ref": "sub/topic.json#/definitions/frame_id"
},
Expand Down Expand Up @@ -72,6 +75,7 @@
"packet_mtu_size",
"launch_hw",
"setup_sensor",
"udp_only",
"frame_id",
"advanced_diagnostics",
"diag_span",
Expand Down
Loading
Loading