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 "laser_assembler/AssembleScans.h"
00043 #include <boost/thread.hpp>
00044 #include <boost/thread/condition.hpp>
00045
00046 using namespace ros;
00047 using namespace sensor_msgs;
00048 using namespace std;
00049
00050 static const string SERVICE_NAME = "assemble_scans";
00051
00052 class TestAssembler : public testing::Test
00053 {
00054 public:
00055
00056 NodeHandle n_;
00057
00058 void SetUp()
00059 {
00060 ROS_INFO("Waiting for service [%s]", SERVICE_NAME.c_str());
00061 ros::service::waitForService(SERVICE_NAME);
00062 ROS_INFO("Service [%s] detected", SERVICE_NAME.c_str());
00063 received_something_ = false;
00064 got_cloud_ = false;
00065 scan_sub_ = n_.subscribe("dummy_scan", 10, &TestAssembler::ScanCallback, (TestAssembler*)this);
00066 }
00067
00068 void ScanCallback(const LaserScanConstPtr& scan_msg)
00069 {
00070 boost::mutex::scoped_lock lock(mutex_);
00071 if (!received_something_)
00072 {
00073
00074 start_time_ = scan_msg->header.stamp;
00075 received_something_ = true;
00076 }
00077 else
00078 {
00079
00080 laser_assembler::AssembleScans assemble_scans;
00081 assemble_scans.request.begin = start_time_;
00082 assemble_scans.request.end = scan_msg->header.stamp;
00083 EXPECT_TRUE(ros::service::call(SERVICE_NAME, assemble_scans));
00084 if(assemble_scans.response.cloud.points.size() > 0)
00085 {
00086 ROS_INFO("Got a cloud with [%u] points. Saving the cloud", (uint32_t)(assemble_scans.response.cloud.points.size()));
00087 cloud_ = assemble_scans.response.cloud;
00088 got_cloud_ = true;
00089 cloud_condition_.notify_all();
00090 }
00091 else
00092 ROS_INFO("Got an empty cloud. Going to try again on the next scan");
00093 }
00094 }
00095
00096 protected:
00097 ros::Subscriber scan_sub_;
00098 bool received_something_;
00099 ros::Time start_time_;
00100 bool got_cloud_;
00101 sensor_msgs::PointCloud cloud_;
00102 boost::mutex mutex_;
00103 boost::condition cloud_condition_;
00104 };
00105
00106
00107 void spinThread()
00108 {
00109 ros::spin();
00110 }
00111
00112
00113 TEST_F(TestAssembler, non_zero_cloud_test)
00114 {
00115
00116 boost::mutex::scoped_lock lock(mutex_);
00117
00118 while(n_.ok() && !got_cloud_)
00119 {
00120 cloud_condition_.timed_wait(lock, boost::posix_time::milliseconds(1000.0f));
00121 }
00122
00123 EXPECT_LT((unsigned int) 0, cloud_.points.size());
00124
00125 SUCCEED();
00126 }
00127
00128 int main(int argc, char** argv)
00129 {
00130 printf("******* Starting application *********\n");
00131
00132 testing::InitGoogleTest(&argc, argv);
00133 ros::init(argc, argv, "test_assembler_node");
00134
00135 boost::thread spin_thread(spinThread);
00136
00137 int result = RUN_ALL_TESTS();
00138
00139 ros::shutdown();
00140
00141 spin_thread.join();
00142 return result;
00143 }