Skip to content

Commit

Permalink
fix(nebula_tests): bugprone-incorrect-roundings (#219)
Browse files Browse the repository at this point in the history
Signed-off-by: kobayu858 <[email protected]>
  • Loading branch information
kobayu858 authored Nov 8, 2024
1 parent 8e75661 commit b48d713
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 6 deletions.
7 changes: 5 additions & 2 deletions nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@

#include <gtest/gtest.h>

#include <cmath>
#include <filesystem>
#include <memory>
#include <regex>
Expand Down Expand Up @@ -180,8 +181,10 @@ Status VelodyneRosDecoderTest::get_parameters(
} else {
double min_angle = fmod(fmod(view_direction + view_width / 2, 2 * M_PI) + 2 * M_PI, 2 * M_PI);
double max_angle = fmod(fmod(view_direction - view_width / 2, 2 * M_PI) + 2 * M_PI, 2 * M_PI);
sensor_configuration.cloud_min_angle = 100 * (2 * M_PI - min_angle) * 180 / M_PI + 0.5;
sensor_configuration.cloud_max_angle = 100 * (2 * M_PI - max_angle) * 180 / M_PI + 0.5;
sensor_configuration.cloud_min_angle =
static_cast<int>(std::lround(100 * (2 * M_PI - min_angle) * 180 / M_PI));
sensor_configuration.cloud_max_angle =
static_cast<int>(std::lround(100 * (2 * M_PI - max_angle) * 180 / M_PI));
if (sensor_configuration.cloud_min_angle == sensor_configuration.cloud_max_angle) {
// avoid returning empty cloud if min_angle = max_angle
sensor_configuration.cloud_min_angle = 0;
Expand Down
7 changes: 5 additions & 2 deletions nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@

#include <gtest/gtest.h>

#include <cmath>
#include <filesystem>
#include <regex>
#include <vector>
Expand Down Expand Up @@ -178,8 +179,10 @@ Status VelodyneRosDecoderTest::get_parameters(
} else {
double min_angle = fmod(fmod(view_direction + view_width / 2, 2 * M_PI) + 2 * M_PI, 2 * M_PI);
double max_angle = fmod(fmod(view_direction - view_width / 2, 2 * M_PI) + 2 * M_PI, 2 * M_PI);
sensor_configuration.cloud_min_angle = 100 * (2 * M_PI - min_angle) * 180 / M_PI + 0.5;
sensor_configuration.cloud_max_angle = 100 * (2 * M_PI - max_angle) * 180 / M_PI + 0.5;
sensor_configuration.cloud_min_angle =
static_cast<int>(std::lround(100 * (2 * M_PI - min_angle) * 180 / M_PI));
sensor_configuration.cloud_max_angle =
static_cast<int>(std::lround(100 * (2 * M_PI - max_angle) * 180 / M_PI));
if (sensor_configuration.cloud_min_angle == sensor_configuration.cloud_max_angle) {
// avoid returning empty cloud if min_angle = max_angle
sensor_configuration.cloud_min_angle = 0;
Expand Down
7 changes: 5 additions & 2 deletions nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include <gtest/gtest.h>
#include <rcutils/time.h>

#include <cmath>
#include <filesystem>
#include <memory>
#include <regex>
Expand Down Expand Up @@ -183,8 +184,10 @@ Status VelodyneRosDecoderTest::get_parameters(
} else {
double min_angle = fmod(fmod(view_direction + view_width / 2, 2 * M_PI) + 2 * M_PI, 2 * M_PI);
double max_angle = fmod(fmod(view_direction - view_width / 2, 2 * M_PI) + 2 * M_PI, 2 * M_PI);
sensor_configuration.cloud_min_angle = 100 * (2 * M_PI - min_angle) * 180 / M_PI + 0.5;
sensor_configuration.cloud_max_angle = 100 * (2 * M_PI - max_angle) * 180 / M_PI + 0.5;
sensor_configuration.cloud_min_angle =
static_cast<int>(std::lround(100 * (2 * M_PI - min_angle) * 180 / M_PI));
sensor_configuration.cloud_max_angle =
static_cast<int>(std::lround(100 * (2 * M_PI - max_angle) * 180 / M_PI));
if (sensor_configuration.cloud_min_angle == sensor_configuration.cloud_max_angle) {
// avoid returning empty cloud if min_angle = max_angle
sensor_configuration.cloud_min_angle = 0;
Expand Down

0 comments on commit b48d713

Please sign in to comment.