test_laser_scan.cpp
Go to the documentation of this file.
1 // Copyright 2023 Ekumen, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <gtest/gtest.h>
16 
17 #include <memory>
18 #include <vector>
19 
20 #include <range/v3/range/conversion.hpp>
21 
22 #if BELUGA_ROS_VERSION == 1
23 #include <boost/smart_ptr.hpp>
24 #endif
25 
27 #include "beluga_ros/messages.hpp"
28 
29 namespace {
30 
31 auto make_message() {
32 #if BELUGA_ROS_VERSION == 2
33  return std::make_shared<beluga_ros::msg::LaserScan>();
34 #elif BELUGA_ROS_VERSION == 1
35  return boost::make_shared<beluga_ros::msg::LaserScan>();
36 #endif
37 }
38 
39 TEST(TestLaserScan, MinMaxRangeFromMessage) {
40  auto message = make_message();
41  message->ranges = std::vector<float>{1., 2., 3.};
42  message->range_min = 10.F;
43  message->range_max = 100.F;
44  auto scan = beluga_ros::LaserScan(message);
45  ASSERT_EQ(scan.min_range(), 10.);
46  ASSERT_EQ(scan.max_range(), 100.);
47 }
48 
49 TEST(TestLaserScan, MinMaxRangeFromConstructor) {
50  auto message = make_message();
51  message->range_min = 10.F;
52  message->range_max = 100.F;
53  const auto origin = Sophus::SE3d{};
54  constexpr auto kMaxBeams = 100UL;
55  constexpr auto kMinRange = 15.;
56  constexpr auto kMaxRange = 95.;
57  auto scan = beluga_ros::LaserScan(message, origin, kMaxBeams, kMinRange, kMaxRange);
58  ASSERT_EQ(scan.min_range(), 15.);
59  ASSERT_EQ(scan.max_range(), 95.);
60 }
61 
62 TEST(TestLaserScan, LimitMaxBeams) {
63  auto message = make_message();
64  message->ranges = std::vector<float>{1., 2., 3.};
65  const auto origin = Sophus::SE3d{};
66  constexpr auto kMaxBeams = 2UL;
67  auto scan = beluga_ros::LaserScan(message, origin, kMaxBeams);
68  auto ranges = scan.ranges() | ranges::to<std::vector>;
69  ASSERT_EQ(ranges.size(), 2UL);
70 }
71 
72 TEST(TestLaserScan, AngleIncrements) {
73  auto message = make_message();
74  message->ranges = std::vector<float>{1., 2., 3.};
75  message->range_min = 0.F;
76  message->range_max = 100.F;
77  message->angle_min = 0.F;
78  message->angle_max = 3.14F;
79  message->angle_increment = 0.1F;
80  const auto origin = Sophus::SE3d{};
81  constexpr auto kMaxBeams = 100UL;
82  auto scan = beluga_ros::LaserScan(message, origin, kMaxBeams);
83  auto angles = scan.angles() | ranges::to<std::vector>;
84  ASSERT_NEAR(angles[0], 0.0, 0.001);
85  ASSERT_NEAR(angles[1], 0.1, 0.001);
86  ASSERT_NEAR(angles[2], 0.2, 0.001);
87 }
88 
89 } // namespace
TEST
TEST(ActionClientDestruction, persistent_goal_handles_1)
beluga_ros.conversion_utils.message
message
Definition: conversion_utils.py:29
laser_scan.hpp
Implementation of sensor_msgs/LaserScan wrapper type.
Sophus::SE3
beluga_ros::LaserScan
Thin wrapper type for 2D sensor_msgs/LaserScan messages.
Definition: laser_scan.hpp:34
messages.hpp


beluga_ros
Author(s):
autogenerated on Tue Jul 16 2024 03:00:02