scenario_simulator_v2 C++ API
test_raycaster.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_RAYCASTER_HPP_
16 #define SIMPLE_SENSOR_SIMULATOR__TEST__TEST_RAYCASTER_HPP_
17 
18 #include <gtest/gtest.h>
19 
20 #include <geometry_msgs/msg/pose.hpp>
21 #include <sensor_msgs/msg/point_cloud2.hpp>
24 #include <vector>
25 
26 #include "../../utils/helper_functions.hpp"
27 
28 using namespace simple_sensor_simulator;
29 using namespace geometry_msgs::msg;
30 
31 constexpr static double degToRad(double deg) { return deg * M_PI / 180.0; }
32 
33 class RaycasterTest : public ::testing::Test
34 {
35 protected:
37  : raycaster_(std::make_unique<Raycaster>()),
38  config_(utils::constructLidarConfiguration("ego", "awf/universe/20240605", 0.0, 0.1)),
39  origin_(utils::makePose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)),
40  box_pose_(utils::makePose(5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)),
41  dummy_entity_status_(utils::makeEntity(
42  box_name_, EntityType::VEHICLE, box_pose_,
43  utils::makeDimensions(box_depth_, box_width_, box_height_)))
44  {
45  raycaster_->setDirection(config_);
46  }
47 
48  std::unique_ptr<Raycaster> raycaster_;
49  simulation_api_schema::LidarConfiguration config_;
50 
51  const float box_depth_{1.0f};
52  const float box_width_{1.0f};
53  const float box_height_{1.0f};
54  const std::string box_name_{"box"};
55 
56  const rclcpp::Time stamp_{0};
57  const std::string frame_id_{"frame_id"};
58 
61 
63 };
64 
65 #endif // SIMPLE_SENSOR_SIMULATOR__TEST__TEST_RAYCASTER_HPP_
Definition: test_raycaster.hpp:34
RaycasterTest()
Definition: test_raycaster.hpp:36
geometry_msgs::msg::Pose origin_
Definition: test_raycaster.hpp:59
geometry_msgs::msg::Pose box_pose_
Definition: test_raycaster.hpp:60
std::unique_ptr< Raycaster > raycaster_
Definition: test_raycaster.hpp:48
simulation_api_schema::LidarConfiguration config_
Definition: test_raycaster.hpp:49
traffic_simulator_msgs::EntityStatus dummy_entity_status_
Definition: test_raycaster.hpp:62
Definition: raycaster.hpp:36
Definition: constants.hpp:19
Definition: lanelet_wrapper.hpp:40
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:66
Definition: helper_functions.hpp:35
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
std::string string
Definition: junit5.hpp:26
traffic_simulator_msgs::EntityStatus EntityStatus
Definition: helper_functions.hpp:32
traffic_simulator_msgs::EntityType EntityType
Definition: helper_functions.hpp:31
geometry_msgs::msg::Pose makePose(double x, double y, double z=0.0, geometry_msgs::msg::Quaternion q=geometry_msgs::msg::Quaternion())
Definition: test_utils.hpp:69