|
| 1 | +// Copyright 2024 Autoware Foundation |
| 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 NDT_SCAN_MATCHER__TEST__STUB_PCD_LOADER_HPP_ |
| 16 | +#define NDT_SCAN_MATCHER__TEST__STUB_PCD_LOADER_HPP_ |
| 17 | + |
| 18 | +#include "test_util.hpp" |
| 19 | + |
| 20 | +#include <rclcpp/rclcpp.hpp> |
| 21 | + |
| 22 | +#include "autoware_map_msgs/srv/get_differential_point_cloud_map.hpp" |
| 23 | + |
| 24 | +class StubPcdLoader : public rclcpp::Node |
| 25 | +{ |
| 26 | + using GetDifferentialPointCloudMap = autoware_map_msgs::srv::GetDifferentialPointCloudMap; |
| 27 | + |
| 28 | +public: |
| 29 | + StubPcdLoader() : Node("stub_pcd_loader") |
| 30 | + { |
| 31 | + get_differential_pcd_maps_service_ = create_service<GetDifferentialPointCloudMap>( |
| 32 | + "pcd_loader_service", std::bind( |
| 33 | + &StubPcdLoader::on_service_get_differential_point_cloud_map, this, |
| 34 | + std::placeholders::_1, std::placeholders::_2)); |
| 35 | + } |
| 36 | + |
| 37 | +private: |
| 38 | + rclcpp::Service<GetDifferentialPointCloudMap>::SharedPtr get_differential_pcd_maps_service_; |
| 39 | + |
| 40 | + bool on_service_get_differential_point_cloud_map( |
| 41 | + GetDifferentialPointCloudMap::Request::SharedPtr req, |
| 42 | + GetDifferentialPointCloudMap::Response::SharedPtr res) |
| 43 | + { |
| 44 | + (void)req; |
| 45 | + autoware_map_msgs::msg::PointCloudMapCellWithID pcd_map_cell_with_id; |
| 46 | + constexpr float max_position = 20.0f; |
| 47 | + constexpr float interval = 0.2f; |
| 48 | + pcd_map_cell_with_id.metadata.min_x = -max_position; |
| 49 | + pcd_map_cell_with_id.metadata.min_y = -max_position; |
| 50 | + pcd_map_cell_with_id.metadata.max_x = max_position; |
| 51 | + pcd_map_cell_with_id.metadata.max_y = max_position; |
| 52 | + pcd_map_cell_with_id.cell_id = "0"; |
| 53 | + pcl::PointCloud<pcl::PointXYZ> cloud = make_sample_pcd(-max_position, max_position, interval); |
| 54 | + pcl::toROSMsg(cloud, pcd_map_cell_with_id.pointcloud); |
| 55 | + res->new_pointcloud_with_ids.push_back(pcd_map_cell_with_id); |
| 56 | + res->header.frame_id = "map"; |
| 57 | + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); |
| 58 | + return true; |
| 59 | + } |
| 60 | +}; |
| 61 | + |
| 62 | +#endif // NDT_SCAN_MATCHER__TEST__STUB_PCD_LOADER_HPP_ |
0 commit comments