15 #ifndef SIMPLE_SENSOR_SIMULATOR__TEST__TEST_LIDAR_SENSOR_HPP_
16 #define SIMPLE_SENSOR_SIMULATOR__TEST__TEST_LIDAR_SENSOR_HPP_
18 #include <gtest/gtest.h>
20 #include <rclcpp/rclcpp.hpp>
21 #include <sensor_msgs/msg/point_cloud2.hpp>
27 #include "../../utils/helper_functions.hpp"
37 rclcpp::init(0,
nullptr);
38 node_ = std::make_shared<rclcpp::Node>(
"lidar_sensor_test_node");
40 initializeEntityStatuses();
42 lidar_ = std::make_unique<LidarSensor<sensor_msgs::msg::PointCloud2>>(0.0, config_, publisher_);
48 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr
publisher_;
49 rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr
subscription_;
53 std::unique_ptr<LidarSensorBase>
lidar_;
54 simulation_api_schema::LidarConfiguration
config_;
57 double current_simulation_time_{1.0};
58 rclcpp::Time current_ros_time_{1};
61 auto initializeEntityStatuses() ->
void
66 "ego", EntityType::EGO,
utils::makePose(5.0, 5.0, 0.0, 0.0, 0.0, 0.0, 1.0), dimensions);
68 "other1", EntityType::VEHICLE,
utils::makePose(-3.0, -3.0, 0.0, 0.0, 0.0, 0.0, 1.0),
71 "other2", EntityType::VEHICLE,
utils::makePose(5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0),
74 status_ = {ego_status, other1_status, other2_status};
77 auto makeRosInterface() ->
void
79 publisher_ = node_->create_publisher<sensor_msgs::msg::PointCloud2>(
"lidar_output", 10);
80 subscription_ = node_->create_subscription<sensor_msgs::msg::PointCloud2>(
82 [
this](
const sensor_msgs::msg::PointCloud2::SharedPtr msg) { received_msg_ = msg; });
Definition: test_lidar_sensor.hpp:32
std::unique_ptr< LidarSensorBase > lidar_
Definition: test_lidar_sensor.hpp:53
~LidarSensorTest()
Definition: test_lidar_sensor.hpp:45
std::vector< EntityStatus > status_
Definition: test_lidar_sensor.hpp:51
rclcpp::Node::SharedPtr node_
Definition: test_lidar_sensor.hpp:47
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr publisher_
Definition: test_lidar_sensor.hpp:48
LidarSensorTest()
Definition: test_lidar_sensor.hpp:34
simulation_api_schema::LidarConfiguration config_
Definition: test_lidar_sensor.hpp:54
sensor_msgs::msg::PointCloud2::SharedPtr received_msg_
Definition: test_lidar_sensor.hpp:55
rclcpp::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr subscription_
Definition: test_lidar_sensor.hpp:49
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