Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <string>
00038 #include <gtest/gtest.h>
00039 #include <ros/ros.h>
00040 #include "sensor_msgs/PointCloud.h"
00041 #include "sensor_msgs/LaserScan.h"
00042 #include "boost/thread.hpp"
00043
00044 using namespace ros;
00045 using namespace sensor_msgs;
00046
00047 int g_argc;
00048 char** g_argv;
00049
00050 class TestAssembler : public testing::Test
00051 {
00052 public:
00053
00054 NodeHandle n_;
00055
00056 sensor_msgs::PointCloud cloud_msg_ ;
00057 boost::mutex cloud_mutex_ ;
00058 sensor_msgs::PointCloud safe_cloud_ ;
00059 int cloud_counter_ ;
00060
00061 LaserScan scan_msg_ ;
00062 boost::mutex scan_mutex_ ;
00063 LaserScan safe_scan_ ;
00064 int scan_counter_ ;
00065
00066
00067 void CloudCallback(const PointCloudConstPtr& cloud_msg)
00068 {
00069 cloud_mutex_.lock() ;
00070 cloud_counter_++ ;
00071 safe_cloud_ = *cloud_msg ;
00072 cloud_mutex_.unlock() ;
00073 ROS_INFO("Got Cloud with %u points", cloud_msg_.get_points_size()) ;
00074 }
00075
00076 void ScanCallback(const LaserScanConstPtr& scan_msg)
00077 {
00078 scan_mutex_.lock() ;
00079 scan_counter_++ ;
00080 safe_scan_ = *scan_msg ;
00081 scan_mutex_.unlock() ;
00082
00083 }
00084
00085 protected:
00087 TestAssembler()
00088 {
00089 cloud_counter_ = 0 ;
00090 scan_counter_ = 0 ;
00091 }
00092
00094 ~TestAssembler()
00095 {
00096
00097 }
00098 };
00099
00100
00101 TEST_F(TestAssembler, test)
00102 {
00103 ROS_INFO("Starting test F");
00104 ros::Subscriber cloud_sub = n_.subscribe("dummy_cloud", 10, &TestAssembler::CloudCallback, (TestAssembler*)this);
00105 ros::Subscriber scan_sub = n_.subscribe("dummy_scan", 10, &TestAssembler::ScanCallback, (TestAssembler*)this);
00106
00107 bool waiting = true;
00108 while(n_.ok() && waiting )
00109 {
00110 ros::spinOnce();
00111 usleep(1e2) ;
00112
00113 scan_mutex_.lock() ;
00114 waiting = (scan_counter_ < 55) ;
00115 scan_mutex_.unlock() ;
00116 }
00117
00118 while(n_.ok() && cloud_counter_ == 0)
00119 {
00120 ROS_INFO("Waiting to get a cloud");
00121 ros::spinOnce();
00122 usleep(5e5);
00123 }
00124
00125 ASSERT_GT(cloud_counter_, 0) ;
00126 ROS_INFO("Got a cloud!");
00127
00128 unsigned int cloud_size ;
00129 cloud_mutex_.lock() ;
00130 cloud_size = safe_cloud_.get_points_size() ;
00131 cloud_mutex_.unlock() ;
00132
00133 EXPECT_LT((unsigned int) 100, cloud_size) ;
00134
00135 SUCCEED();
00136 }
00137
00138 int main(int argc, char** argv)
00139 {
00140 printf("******* Starting application *********\n");
00141
00142 testing::InitGoogleTest(&argc, argv);
00143 ros::init(argc, argv, "test_assembler_node");
00144
00145 return RUN_ALL_TESTS();
00146 }