test_expansion_resetting.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 offset_x,
00052     const float offset_y,
00053     const float offset_z)
00054 {
00055   cloud.height = 1;
00056   cloud.is_bigendian = false;
00057   cloud.is_dense = false;
00058   sensor_msgs::PointCloud2Modifier modifier(cloud);
00059   modifier.setPointCloud2Fields(
00060       4,
00061       "x", 1, sensor_msgs::PointField::FLOAT32,
00062       "y", 1, sensor_msgs::PointField::FLOAT32,
00063       "z", 1, sensor_msgs::PointField::FLOAT32,
00064       "intensity", 1, sensor_msgs::PointField::FLOAT32);
00065 
00066   class Point
00067   {
00068   public:
00069     float x_, y_, z_;
00070     Point(const float x, const float y, const float z)
00071       : x_(x)
00072       , y_(y)
00073       , z_(z)
00074     {
00075     }
00076   };
00077   std::vector<Point> points;
00078   // Draw cube
00079   for (float x = -1; x < 1; x += 0.05)
00080   {
00081     for (float y = -1; y < 1; y += 0.05)
00082     {
00083       points.push_back(Point(x / 2 + offset_x, y + offset_y, 1.0 + offset_z));
00084       points.push_back(Point(x / 2 + offset_x, y + offset_y, -1.0 + offset_z));
00085       points.push_back(Point(1.0 / 2 + offset_x, y + offset_y, x + offset_z));
00086       points.push_back(Point(-1.0 / 2 + offset_x, y + offset_y, x + offset_z));
00087       points.push_back(Point(x / 2 + offset_x, 1.0 + offset_y, y + offset_z));
00088       points.push_back(Point(x / 2 + offset_x, -1.0 + offset_y, y + offset_z));
00089     }
00090   }
00091 
00092   modifier.resize(points.size());
00093   cloud.width = points.size();
00094   sensor_msgs::PointCloud2Iterator<float> iter_x(cloud, "x");
00095   sensor_msgs::PointCloud2Iterator<float> iter_y(cloud, "y");
00096   sensor_msgs::PointCloud2Iterator<float> iter_z(cloud, "z");
00097 
00098   for (const Point& p : points)
00099   {
00100     *iter_x = p.x_;
00101     *iter_y = p.y_;
00102     *iter_z = p.z_;
00103     ++iter_x;
00104     ++iter_y;
00105     ++iter_z;
00106   }
00107 }
00108 
00109 inline sensor_msgs::PointCloud2 generateMapMsg(
00110     const float offset_x,
00111     const float offset_y,
00112     const float offset_z)
00113 {
00114   sensor_msgs::PointCloud2 cloud;
00115   generateSamplePointcloud2(cloud, offset_x, offset_y, offset_z);
00116   cloud.header.frame_id = "map";
00117   return cloud;
00118 }
00119 inline sensor_msgs::PointCloud2 generateCloudMsg()
00120 {
00121   sensor_msgs::PointCloud2 cloud;
00122   generateSamplePointcloud2(cloud, 0, 0, 0);
00123   cloud.header.frame_id = "base_link";
00124   cloud.header.stamp = ros::Time::now();
00125   return cloud;
00126 }
00127 inline sensor_msgs::Imu generateImuMsg()
00128 {
00129   sensor_msgs::Imu imu;
00130   imu.header.frame_id = "base_link";
00131   imu.header.stamp = ros::Time::now();
00132   imu.orientation.w = 1;
00133   imu.linear_acceleration.z = 9.8;
00134   return imu;
00135 }
00136 inline nav_msgs::Odometry generateOdomMsg()
00137 {
00138   nav_msgs::Odometry odom;
00139   odom.header.frame_id = "odom";
00140   odom.header.stamp = ros::Time::now();
00141   odom.pose.pose.position.x = 1;
00142   odom.pose.pose.orientation.w = 1;
00143   return odom;
00144 }
00145 }  // namespace
00146 
00147 TEST(ExpansionResetting, ExpandAndResume)
00148 {
00149   geometry_msgs::PoseArray::ConstPtr poses;
00150   mcl_3dl_msgs::Status::ConstPtr status;
00151 
00152   const boost::function<void(const geometry_msgs::PoseArray::ConstPtr&)> cb_pose =
00153       [&poses](const geometry_msgs::PoseArray::ConstPtr& msg) -> void
00154   {
00155     poses = msg;
00156   };
00157   const boost::function<void(const mcl_3dl_msgs::Status::ConstPtr&)> cb_status =
00158       [&status](const mcl_3dl_msgs::Status::ConstPtr& msg) -> void
00159   {
00160     status = msg;
00161   };
00162 
00163   ros::NodeHandle nh("");
00164   ros::Subscriber sub_pose = nh.subscribe("mcl_3dl/particles", 1, cb_pose);
00165   ros::Subscriber sub_status = nh.subscribe("mcl_3dl/status", 1, cb_status);
00166 
00167   ros::ServiceClient src_expansion_resetting =
00168       nh.serviceClient<std_srvs::TriggerRequest, std_srvs::TriggerResponse>(
00169           "expansion_resetting");
00170 
00171   ros::Publisher pub_mapcloud = nh.advertise<sensor_msgs::PointCloud2>("mapcloud", 1, true);
00172   ros::Publisher pub_cloud = nh.advertise<sensor_msgs::PointCloud2>("cloud", 1);
00173   ros::Publisher pub_imu = nh.advertise<sensor_msgs::Imu>("imu/data", 1);
00174   ros::Publisher pub_odom = nh.advertise<nav_msgs::Odometry>("odom", 1);
00175 
00176   const float offset_x = 1;
00177   const float offset_y = 0;
00178   const float offset_z = 0;
00179   pub_mapcloud.publish(generateMapMsg(offset_x, offset_y, offset_z));
00180 
00181   ros::Duration(1.0).sleep();
00182   ros::Rate rate(10);
00183   // Wait until finishing expansion resetting
00184   for (int i = 0; i < 40; ++i)
00185   {
00186     rate.sleep();
00187     ros::spinOnce();
00188     if (status && status->status == mcl_3dl_msgs::Status::EXPANSION_RESETTING)
00189       i = 0;
00190     pub_cloud.publish(generateCloudMsg());
00191     pub_imu.publish(generateImuMsg());
00192     pub_odom.publish(generateOdomMsg());
00193   }
00194   ASSERT_TRUE(ros::ok());
00195 
00196   ASSERT_TRUE(static_cast<bool>(status));
00197   ASSERT_TRUE(static_cast<bool>(poses));
00198 
00199   const tf2::Transform true_pose(
00200       tf2::Quaternion(0, 0, 0, 1), tf2::Vector3(offset_x, offset_y, offset_z));
00201   bool found_true_positive(false);
00202   for (const auto& pose : poses->poses)
00203   {
00204     tf2::Transform particle_pose;
00205     tf2::fromMsg(pose, particle_pose);
00206 
00207     const tf2::Transform tf_diff = particle_pose.inverse() * true_pose;
00208     if (tf_diff.getOrigin().length() < 2e-1 &&
00209         fabs(tf2::getYaw(tf_diff.getRotation())) < 2e-1)
00210       found_true_positive = true;
00211   }
00212   ASSERT_TRUE(found_true_positive);
00213 }
00214 
00215 int main(int argc, char** argv)
00216 {
00217   testing::InitGoogleTest(&argc, argv);
00218   ros::init(argc, argv, "test_expansion_resetting");
00219 
00220   return RUN_ALL_TESTS();
00221 }


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