Skip to content

Commit

Permalink
Update get_n_returns to include FUSA profile
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu committed May 28, 2024
1 parent b81bb22 commit 313f8d9
Showing 1 changed file with 5 additions and 4 deletions.
9 changes: 5 additions & 4 deletions src/os_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,11 @@ bool is_legacy_lidar_profile(const sensor::sensor_info& info) {

int get_n_returns(const sensor::sensor_info& info) {
using sensor::UDPProfileLidar;
return info.format.udp_profile_lidar ==
UDPProfileLidar::PROFILE_RNG19_RFL8_SIG16_NIR16_DUAL
? 2
: 1;
if (info.format.udp_profile_lidar == UDPProfileLidar::PROFILE_RNG19_RFL8_SIG16_NIR16_DUAL ||
info.format.udp_profile_lidar == UDPProfileLidar::PROFILE_FUSA_RNG15_RFL8_NIR8_DUAL)
return 2;

return 1;
}

size_t get_beams_count(const sensor::sensor_info& info) {
Expand Down

0 comments on commit 313f8d9

Please sign in to comment.