scenario_simulator_v2 C++ API
test_lidar_sensor.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
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 #ifndef SIMPLE_SENSOR_SIMULATOR__TEST__TEST_LIDAR_SENSOR_HPP_
16 #define SIMPLE_SENSOR_SIMULATOR__TEST__TEST_LIDAR_SENSOR_HPP_
17 
18 #include <gtest/gtest.h>
19 
20 #include <rclcpp/rclcpp.hpp>
21 #include <sensor_msgs/msg/point_cloud2.hpp>
22 #include <set>
24 #include <string>
25 #include <vector>
26 
27 #include "../../utils/helper_functions.hpp"
28 
29 using namespace simple_sensor_simulator;
30 
31 class LidarSensorTest : public ::testing::Test
32 {
33 protected:
34  LidarSensorTest() : config_(utils::constructLidarConfiguration("ego", "awf/universe", 0.0, 0.5))
35  {
36  rclcpp::init(0, nullptr);
37  node_ = std::make_shared<rclcpp::Node>("lidar_sensor_test_node");
38  makeRosInterface();
39  initializeEntityStatuses();
40 
41  lidar_ = std::make_unique<LidarSensor<sensor_msgs::msg::PointCloud2>>(0.0, config_, publisher_);
42  }
43 
44  ~LidarSensorTest() { rclcpp::shutdown(); }
45 
46  rclcpp::Node::SharedPtr node_;
47  rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr publisher_;
48  rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr subscription_;
49 
50  std::vector<EntityStatus> status_;
51 
52  std::unique_ptr<LidarSensorBase> lidar_;
53  simulation_api_schema::LidarConfiguration config_;
54  sensor_msgs::msg::PointCloud2::SharedPtr received_msg_;
55 
56  double current_simulation_time_{1.0};
57  rclcpp::Time current_ros_time_{1};
58 
59 private:
60  auto initializeEntityStatuses() -> void
61  {
62  const auto dimensions = utils::makeDimensions(4.5, 2.0, 1.5);
63 
64  const auto ego_status = utils::makeEntity(
65  "ego", EntityType::EGO, utils::makePose(5.0, 5.0, 0.0, 0.0, 0.0, 0.0, 1.0), dimensions);
66  const auto other1_status = utils::makeEntity(
67  "other1", EntityType::VEHICLE, utils::makePose(-3.0, -3.0, 0.0, 0.0, 0.0, 0.0, 1.0),
68  dimensions);
69  const auto other2_status = utils::makeEntity(
70  "other2", EntityType::VEHICLE, utils::makePose(5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0),
71  dimensions);
72 
73  status_ = {ego_status, other1_status, other2_status};
74  }
75 
76  auto makeRosInterface() -> void
77  {
78  publisher_ = node_->create_publisher<sensor_msgs::msg::PointCloud2>("lidar_output", 10);
79  subscription_ = node_->create_subscription<sensor_msgs::msg::PointCloud2>(
80  "lidar_output", 10,
81  [this](const sensor_msgs::msg::PointCloud2::SharedPtr msg) { received_msg_ = msg; });
82  }
83 };
84 #endif // SIMPLE_SENSOR_SIMULATOR__TEST__TEST_LIDAR_SENSOR_HPP_
Definition: test_lidar_sensor.hpp:32
std::unique_ptr< LidarSensorBase > lidar_
Definition: test_lidar_sensor.hpp:52
~LidarSensorTest()
Definition: test_lidar_sensor.hpp:44
std::vector< EntityStatus > status_
Definition: test_lidar_sensor.hpp:50
rclcpp::Node::SharedPtr node_
Definition: test_lidar_sensor.hpp:46
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr publisher_
Definition: test_lidar_sensor.hpp:47
LidarSensorTest()
Definition: test_lidar_sensor.hpp:34
simulation_api_schema::LidarConfiguration config_
Definition: test_lidar_sensor.hpp:53
sensor_msgs::msg::PointCloud2::SharedPtr received_msg_
Definition: test_lidar_sensor.hpp:54
rclcpp::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr subscription_
Definition: test_lidar_sensor.hpp:48
Definition: constants.hpp:19
Definition: helper_functions.hpp:35
auto makePose(const double px, const double py, const double pz, const double ox, const double oy, const double oz, const double ow) -> geometry_msgs::msg::Pose
Definition: helper_functions.hpp:45
auto constructLidarConfiguration(const std::string &entity, const std::string &architecture_type, const double lidar_sensor_delay, const double horizontal_resolution) -> const simulation_api_schema::LidarConfiguration
Definition: helper_functions.hpp:60
auto makeEntity(const std::string &name, const EntityType::Enum type, const EntitySubtype::Enum subtype, const geometry_msgs::msg::Pose &pose, const geometry_msgs::msg::Vector3 &dimensions) -> EntityStatus
Definition: helper_functions.hpp:125
auto makeDimensions(const double x, const double y, const double z) -> geometry_msgs::msg::Vector3
Definition: helper_functions.hpp:54