integrationtest_scan_topic_node.cpp
Go to the documentation of this file.
1 // Copyright (c) 2020 Pilz GmbH & Co. KG
2 //
3 // This program is free software: you can redistribute it and/or modify
4 // it under the terms of the GNU Lesser General Public License as published by
5 // the Free Software Foundation, either version 3 of the License, or
6 // (at your option) any later version.
7 //
8 // This program is distributed in the hope that it will be useful,
9 // but WITHOUT ANY WARRANTY; without even the implied warranty of
10 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 // GNU Lesser General Public License for more details.
12 //
13 // You should have received a copy of the GNU Lesser General Public License
14 // along with this program. If not, see <https://www.gnu.org/licenses/>.
15 
16 #include <gtest/gtest.h>
18 #include "psen_scan/laserscan.h"
19 #include "psen_scan/mock_scanner.h"
20 
21 using namespace psen_scan;
22 using namespace psen_scan_test;
23 using ::testing::Return;
24 using ::testing::DoAll;
25 
26 ACTION(ROS_SHUTDOWN)
27 {
28  sleep(1);
29  ros::shutdown();
30 }
31 
32 ACTION(PSEN_SCAN_PAUSE)
33 {
34  usleep(30000);
35 }
36 
41 int main(int argc, char** argv)
42 {
43  ros::init(argc, argv, "integrationtest_scan_topic_node");
44  ros::NodeHandle nh("~");
45 
47  laser_scan_fake.measures_.push_back(1);
49  laser_scan_error.measures_.push_back(1);
50 
51  std::unique_ptr<MockScanner> mock_scanner = std::unique_ptr<MockScanner>(new MockScanner());
52 
53  EXPECT_CALL(*(mock_scanner), getCompleteScan()).Times(1).WillOnce(DoAll(ROS_SHUTDOWN(), Return(laser_scan_error)));
54 
55  EXPECT_CALL(*(mock_scanner), getCompleteScan())
56  .Times(100)
57  .WillRepeatedly(DoAll(PSEN_SCAN_PAUSE(), Return(laser_scan_fake)))
58  .RetiresOnSaturation();
59 
60  ROSScannerNode ros_scanner_node(nh,
61  "scan",
62  "scanner",
63  0, // every frame
64  Degree(137.5),
65  std::move(mock_scanner));
66 
67  ros_scanner_node.processingLoop();
68 
69  return 0;
70 }
int main(int argc, char **argv)
This node is used in an integrationtest that checks that messages are correctly published on the &#39;sca...
Class implements a ROS-Node for the PSENscan safety laser scanner.
Class to model angles in degrees from user&#39;s perspective.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Class to hold the data for one laserscan without depencies to ROS.
Definition: laserscan.h:29
std::vector< uint16_t > measures_
Definition: laserscan.h:36
ACTION(ROS_SHUTDOWN)
ROSCPP_DECL void shutdown()
Class to model angles in PSENscan internal format (tenth of degrees)
void processingLoop()
endless loop for processing incoming UDP data from the laser scanner


psen_scan
Author(s):
autogenerated on Mon Feb 28 2022 23:16:20