test_global_localization.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2018, the mcl_3dl authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 
00032 #include <geometry_msgs/PoseArray.h>
00033 #include <mcl_3dl_msgs/Status.h>
00034 #include <nav_msgs/Odometry.h>
00035 #include <sensor_msgs/Imu.h>
00036 #include <sensor_msgs/PointCloud2.h>
00037 #include <sensor_msgs/point_cloud2_iterator.h>
00038 #include <std_srvs/Trigger.h>
00039 #include <tf2/utils.h>
00040 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00041 
00042 #include <random>
00043 #include <vector>
00044 
00045 #include <gtest/gtest.h>
00046 
00047 namespace
00048 {
00049 void generateSamplePointcloud2(
00050     sensor_msgs::PointCloud2& cloud,
00051     const float x0,
00052     const float y0,
00053     const float x1,
00054     const float y1,
00055     const float offset_x,
00056     const float offset_y,
00057     const float offset_z,
00058     const float offset_yaw)
00059 {
00060   std::random_device seed;
00061   std::default_random_engine engine(seed());
00062   std::normal_distribution<float> rand(0, 0.01);
00063 
00064   cloud.height = 1;
00065   cloud.is_bigendian = false;
00066   cloud.is_dense = false;
00067   sensor_msgs::PointCloud2Modifier modifier(cloud);
00068   modifier.setPointCloud2Fields(
00069       4,
00070       "x", 1, sensor_msgs::PointField::FLOAT32,
00071       "y", 1, sensor_msgs::PointField::FLOAT32,
00072       "z", 1, sensor_msgs::PointField::FLOAT32,
00073       "intensity", 1, sensor_msgs::PointField::FLOAT32);
00074 
00075   class Point
00076   {
00077   public:
00078     float x_, y_, z_;
00079     Point(const float x, const float y, const float z)
00080       : x_(x)
00081       , y_(y)
00082       , z_(z)
00083     {
00084     }
00085   };
00086   std::vector<Point> points;
00087   const float grid_xy = 0.15;
00088   const float grid_z = 0.1;
00089   const float floor_size = 6.0;
00090   // Draw floor
00091   for (float x = -floor_size; x < floor_size; x += grid_xy)
00092     for (float y = -floor_size; y < floor_size; y += grid_xy)
00093       if (x0 < x && x < x1 && y0 < y && y < y1)
00094         points.push_back(Point(x, y, 0.0));
00095   // Draw objects
00096   for (float x = -2; x < 1.6; x += grid_xy)
00097     if (x0 < x && x < x1)
00098       for (float z = 0.5; z < 1.5; z += grid_z)
00099         points.push_back(Point(x, 1.6, z));
00100   for (float y = -0.5; y < 1.6; y += grid_xy)
00101     if (y0 < y && y < y1)
00102       for (float z = 0.5; z < 2.0; z += grid_z)
00103         points.push_back(Point(1.6, y, z));
00104   for (float x = 0; x < 1.6; x += grid_xy)
00105     if (x0 < x && x < x1)
00106       for (float z = 0.5; z < 2.0; z += grid_z)
00107         points.push_back(Point(x, -2.1 + x, z));
00108 
00109   const float o_cos = cosf(offset_yaw);
00110   const float o_sin = sinf(offset_yaw);
00111   modifier.resize(points.size());
00112   cloud.width = points.size();
00113   sensor_msgs::PointCloud2Iterator<float> iter_x(cloud, "x");
00114   sensor_msgs::PointCloud2Iterator<float> iter_y(cloud, "y");
00115   sensor_msgs::PointCloud2Iterator<float> iter_z(cloud, "z");
00116 
00117   for (const Point& p : points)
00118   {
00119     *iter_x = p.x_ * o_cos - p.y_ * o_sin + offset_x + rand(engine);
00120     *iter_y = p.x_ * o_sin + p.y_ * o_cos + offset_y + rand(engine);
00121     *iter_z = p.z_ + offset_z + rand(engine);
00122     ++iter_x;
00123     ++iter_y;
00124     ++iter_z;
00125   }
00126 }
00127 
00128 inline sensor_msgs::PointCloud2 generateMapMsg()
00129 {
00130   sensor_msgs::PointCloud2 cloud;
00131   generateSamplePointcloud2(cloud, -100, -100, 100, 100, 0, 0, 0, 0);
00132   cloud.header.frame_id = "map";
00133   return cloud;
00134 }
00135 inline sensor_msgs::PointCloud2 generateCloudMsg(
00136     const float offset_x,
00137     const float offset_y,
00138     const float offset_z,
00139     const float offset_yaw)
00140 {
00141   sensor_msgs::PointCloud2 cloud;
00142   generateSamplePointcloud2(
00143       cloud, -2, -2, 2, 2,
00144       offset_x, offset_y, offset_z, offset_yaw);
00145   cloud.header.frame_id = "laser";
00146   cloud.header.stamp = ros::Time::now();
00147   return cloud;
00148 }
00149 inline sensor_msgs::Imu generateImuMsg()
00150 {
00151   sensor_msgs::Imu imu;
00152   imu.header.frame_id = "base_link";
00153   imu.header.stamp = ros::Time::now();
00154   imu.orientation.w = 1;
00155   imu.linear_acceleration.z = 9.8;
00156   return imu;
00157 }
00158 inline nav_msgs::Odometry generateOdomMsg()
00159 {
00160   nav_msgs::Odometry odom;
00161   odom.header.frame_id = "odom";
00162   odom.header.stamp = ros::Time::now();
00163   odom.pose.pose.position.y = 5;
00164   odom.pose.pose.orientation.w = 1;
00165   return odom;
00166 }
00167 }  // namespace
00168 
00169 TEST(GlobalLocalization, Localize)
00170 {
00171   geometry_msgs::PoseArray::ConstPtr poses;
00172   mcl_3dl_msgs::Status::ConstPtr status;
00173 
00174   const boost::function<void(const geometry_msgs::PoseArray::ConstPtr&)> cb_pose =
00175       [&poses](const geometry_msgs::PoseArray::ConstPtr& msg) -> void
00176   {
00177     poses = msg;
00178   };
00179   const boost::function<void(const mcl_3dl_msgs::Status::ConstPtr&)> cb_status =
00180       [&status](const mcl_3dl_msgs::Status::ConstPtr& msg) -> void
00181   {
00182     status = msg;
00183   };
00184 
00185   ros::NodeHandle nh("");
00186   ros::Subscriber sub_pose = nh.subscribe("mcl_3dl/particles", 1, cb_pose);
00187   ros::Subscriber sub_status = nh.subscribe("mcl_3dl/status", 1, cb_status);
00188 
00189   ros::ServiceClient src_global_localization =
00190       nh.serviceClient<std_srvs::TriggerRequest, std_srvs::TriggerResponse>(
00191           "global_localization");
00192 
00193   ros::Publisher pub_mapcloud = nh.advertise<sensor_msgs::PointCloud2>("mapcloud", 1, true);
00194   ros::Publisher pub_cloud = nh.advertise<sensor_msgs::PointCloud2>("cloud", 1);
00195   ros::Publisher pub_imu = nh.advertise<sensor_msgs::Imu>("imu/data", 1);
00196   ros::Publisher pub_odom = nh.advertise<nav_msgs::Odometry>("odom", 1);
00197 
00198   pub_mapcloud.publish(generateMapMsg());
00199 
00200   for (float offset_x = -0.5; offset_x <= 0.51; offset_x += 1.0)
00201   {
00202     for (float offset_yaw = -M_PI / 2; offset_yaw <= M_PI / 2 + 0.1; offset_yaw += M_PI)
00203     {
00204       const float laser_frame_height = 0.5;
00205       const float offset_y = 0.54;
00206       const float offset_z = 0.0;
00207 
00208       ros::Rate rate(10);
00209       // Wait until mcl_3dl initialization
00210       while (ros::ok())
00211       {
00212         rate.sleep();
00213         ros::spinOnce();
00214         if (status && status->status == mcl_3dl_msgs::Status::NORMAL)
00215           break;
00216         pub_cloud.publish(
00217             generateCloudMsg(offset_x, offset_y, offset_z - laser_frame_height, offset_yaw));
00218         pub_imu.publish(generateImuMsg());
00219         pub_odom.publish(generateOdomMsg());
00220       }
00221       ASSERT_TRUE(ros::ok());
00222 
00223       std_srvs::Trigger trigger;
00224       ASSERT_TRUE(src_global_localization.call(trigger));
00225       ros::spinOnce();
00226 
00227       // Wait until starting global localization
00228       while (ros::ok())
00229       {
00230         rate.sleep();
00231         ros::spinOnce();
00232         if (status && status->status == mcl_3dl_msgs::Status::GLOBAL_LOCALIZATION)
00233           break;
00234         pub_cloud.publish(
00235             generateCloudMsg(offset_x, offset_y, offset_z - laser_frame_height, offset_yaw));
00236         pub_imu.publish(generateImuMsg());
00237         pub_odom.publish(generateOdomMsg());
00238       }
00239       ASSERT_TRUE(ros::ok());
00240 
00241       // Wait until finishing global localization
00242       while (ros::ok())
00243       {
00244         rate.sleep();
00245         ros::spinOnce();
00246         if (status && status->status == mcl_3dl_msgs::Status::NORMAL)
00247           break;
00248         pub_cloud.publish(
00249             generateCloudMsg(offset_x, offset_y, offset_z - laser_frame_height, offset_yaw));
00250         pub_imu.publish(generateImuMsg());
00251         pub_odom.publish(generateOdomMsg());
00252       }
00253       ASSERT_TRUE(ros::ok());
00254 
00255       // Wait to improve accuracy
00256       for (int i = 0; i < 40; ++i)
00257       {
00258         rate.sleep();
00259         ros::spinOnce();
00260         pub_cloud.publish(
00261             generateCloudMsg(offset_x, offset_y, offset_z - laser_frame_height, offset_yaw));
00262         pub_imu.publish(generateImuMsg());
00263         pub_odom.publish(generateOdomMsg());
00264       }
00265       ASSERT_TRUE(ros::ok());
00266 
00267       ASSERT_TRUE(static_cast<bool>(status));
00268       ASSERT_TRUE(static_cast<bool>(poses));
00269 
00270       const tf2::Transform true_pose(
00271           tf2::Quaternion(0, 0, sinf(-offset_yaw / 2), cosf(-offset_yaw / 2)),
00272           tf2::Vector3(
00273               -(offset_x * cos(-offset_yaw) - offset_y * sin(-offset_yaw)),
00274               -(offset_x * sin(-offset_yaw) + offset_y * cos(-offset_yaw)),
00275               -offset_z));
00276       bool found_true_positive(false);
00277       for (const auto& pose : poses->poses)
00278       {
00279         tf2::Transform particle_pose;
00280         tf2::fromMsg(pose, particle_pose);
00281 
00282         const tf2::Transform tf_diff = particle_pose.inverse() * true_pose;
00283         if (tf_diff.getOrigin().length() < 2e-1 &&
00284             fabs(tf2::getYaw(tf_diff.getRotation())) < 2e-1)
00285           found_true_positive = true;
00286       }
00287       ASSERT_TRUE(found_true_positive);
00288     }
00289   }
00290 }
00291 
00292 int main(int argc, char** argv)
00293 {
00294   testing::InitGoogleTest(&argc, argv);
00295   ros::init(argc, argv, "test_global_localization");
00296 
00297   return RUN_ALL_TESTS();
00298 }


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 20 2019 20:04:43