16 #include <gtest/gtest.h> 23 using ::testing::Return;
24 using ::testing::DoAll;
41 int main(
int argc,
char** argv)
43 ros::init(argc, argv,
"integrationtest_scan_topic_node");
51 std::unique_ptr<MockScanner> mock_scanner = std::unique_ptr<MockScanner>(
new MockScanner());
53 EXPECT_CALL(*(mock_scanner), getCompleteScan()).Times(1).WillOnce(DoAll(ROS_SHUTDOWN(), Return(laser_scan_error)));
55 EXPECT_CALL(*(mock_scanner), getCompleteScan())
57 .WillRepeatedly(DoAll(PSEN_SCAN_PAUSE(), Return(laser_scan_fake)))
58 .RetiresOnSaturation();
65 std::move(mock_scanner));
int main(int argc, char **argv)
This node is used in an integrationtest that checks that messages are correctly published on the 'sca...
Class implements a ROS-Node for the PSENscan safety laser scanner.
Class to model angles in degrees from user'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.
std::vector< uint16_t > measures_
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