|
| 1 | +// Copyright (c) 2017 Alberto J. Tudela Roldán |
| 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 | +#include "rclcpp/rclcpp.hpp" |
| 17 | +#include "laser_segmentation/laser_segmentation.hpp" |
| 18 | + |
| 19 | +TEST(LaserSegmentationTest, integration) { |
| 20 | + rclcpp::init(0, nullptr); |
| 21 | + // Create the scan publisher node |
| 22 | + auto pub_node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("scan_publisher"); |
| 23 | + pub_node->configure(); |
| 24 | + // Create a publisher for the scan |
| 25 | + auto scan_pub = pub_node->create_publisher<sensor_msgs::msg::LaserScan>("scan", 1); |
| 26 | + ASSERT_EQ(scan_pub->get_subscription_count(), 0); |
| 27 | + EXPECT_FALSE(scan_pub->is_activated()); |
| 28 | + // Activate the publisher |
| 29 | + pub_node->activate(); |
| 30 | + EXPECT_TRUE(scan_pub->is_activated()); |
| 31 | + scan_pub->on_activate(); |
| 32 | + auto pub_thread = std::thread([&]() {rclcpp::spin(pub_node->get_node_base_interface());}); |
| 33 | + |
| 34 | + // Create and configure the laser_segmentation node |
| 35 | + auto seg_node = std::make_shared<laserSegmentation>(); |
| 36 | + // Set some parameters |
| 37 | + nav2_util::declare_parameter_if_not_declared( |
| 38 | + seg_node, "min_points_segment", rclcpp::ParameterValue(1)); |
| 39 | + nav2_util::declare_parameter_if_not_declared( |
| 40 | + seg_node, "max_points_segment", rclcpp::ParameterValue(3)); |
| 41 | + seg_node->configure(); |
| 42 | + seg_node->activate(); |
| 43 | + |
| 44 | + // Create a scan message with three points |
| 45 | + sensor_msgs::msg::LaserScan scan; |
| 46 | + scan.header.frame_id = "laser_frame"; |
| 47 | + scan.angle_min = -M_PI / 2; |
| 48 | + scan.angle_max = M_PI / 2; |
| 49 | + scan.angle_increment = M_PI / 180; |
| 50 | + scan.time_increment = 0.1; |
| 51 | + scan.scan_time = 0.1; |
| 52 | + scan.range_min = 0.0; |
| 53 | + scan.range_max = 10.0; |
| 54 | + scan.ranges.push_back(1.0); |
| 55 | + scan.ranges.push_back(1.1); |
| 56 | + scan.ranges.push_back(2.0); |
| 57 | + scan.ranges.push_back(2.1); |
| 58 | + scan.ranges.push_back(3.0); |
| 59 | + scan.ranges.push_back(3.2); |
| 60 | + scan.ranges.push_back(12.0); |
| 61 | + // Publish the message |
| 62 | + scan_pub->publish(scan); |
| 63 | + |
| 64 | + // Create the segments subscriber node |
| 65 | + auto sub_node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("segment_subscriber"); |
| 66 | + sub_node->configure(); |
| 67 | + sub_node->activate(); |
| 68 | + // Create a subscriber for the segments |
| 69 | + auto seg_sub = sub_node->create_subscription<slg_msgs::msg::SegmentArray>( |
| 70 | + "segments", 1, |
| 71 | + [&](const slg_msgs::msg::SegmentArray msg) { |
| 72 | + EXPECT_EQ(msg.segments.size(), 1); |
| 73 | + RCLCPP_INFO(sub_node->get_logger(), "Segment received: %ld", msg.segments.size()); |
| 74 | + }); |
| 75 | + auto sub_thread = std::thread([&]() {rclcpp::spin(sub_node->get_node_base_interface());}); |
| 76 | + |
| 77 | + // Spin the laser_segmentation node |
| 78 | + rclcpp::spin_some(seg_node->get_node_base_interface()); |
| 79 | + |
| 80 | + // Check the results: now, the scan should have a subscription |
| 81 | + // and the segment should have a publisher |
| 82 | + EXPECT_EQ(scan_pub->get_subscription_count(), 1); |
| 83 | + EXPECT_EQ(seg_sub->get_publisher_count(), 1); |
| 84 | + |
| 85 | + // Deactivate the nodes |
| 86 | + seg_node->deactivate(); |
| 87 | + pub_node->deactivate(); |
| 88 | + sub_node->deactivate(); |
| 89 | + rclcpp::shutdown(); |
| 90 | + // Have to join thread after rclcpp is shut down otherwise test hangs. |
| 91 | + sub_thread.join(); |
| 92 | + pub_thread.join(); |
| 93 | +} |
0 commit comments