test_landmark.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, the mcl_3dl authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <limits>
31 #include <utility>
32 #include <vector>
33 
34 #include <ros/ros.h>
35 
36 #include <geometry_msgs/PoseArray.h>
37 #include <geometry_msgs/PoseWithCovarianceStamped.h>
38 
39 #include <gtest/gtest.h>
40 
41 namespace
42 {
43 inline geometry_msgs::PoseWithCovarianceStamped generatePoseWithCov(
44  const float y, const float y_var, const float var_measure = 0.0)
45 {
46  geometry_msgs::PoseWithCovarianceStamped pose;
47  pose.header.frame_id = "map";
48  pose.header.stamp = ros::Time::now();
49  pose.pose.pose.position.y = y;
50  pose.pose.pose.orientation.w = 1.0;
51  pose.pose.covariance[6 * 0 + 0] = var_measure;
52  pose.pose.covariance[6 * 1 + 1] = y_var;
53  pose.pose.covariance[6 * 2 + 2] = var_measure;
54  pose.pose.covariance[6 * 3 + 3] = var_measure;
55  pose.pose.covariance[6 * 4 + 4] = var_measure;
56  pose.pose.covariance[6 * 5 + 5] = var_measure;
57  return pose;
58 }
59 std::pair<float, float> getMean(const std::vector<geometry_msgs::Pose>& poses)
60 {
61  float mean = 0;
62  for (const geometry_msgs::Pose p : poses)
63  {
64  mean += p.position.y;
65  }
66  mean /= poses.size();
67 
68  float root_mean = 0;
69  for (const geometry_msgs::Pose p : poses)
70  {
71  root_mean += std::pow(p.position.y - mean, 2.0f);
72  }
73  root_mean /= poses.size();
74 
75  return std::pair<float, float>(mean, root_mean);
76 }
77 } // namespace
78 TEST(Landmark, Measurement)
79 {
80  geometry_msgs::PoseArray::ConstPtr poses;
81 
82  const boost::function<void(const geometry_msgs::PoseArray::ConstPtr&)> cb_pose =
83  [&poses](const geometry_msgs::PoseArray::ConstPtr& msg) -> void
84  {
85  poses = msg;
86  };
87 
88  ros::NodeHandle nh("");
89  ros::Subscriber sub_pose = nh.subscribe("mcl_3dl/particles", 1, cb_pose);
90  ros::Publisher pub_init =
91  nh.advertise<geometry_msgs::PoseWithCovarianceStamped>("initialpose", 1, true);
92  ros::Publisher pub_landmark =
93  nh.advertise<geometry_msgs::PoseWithCovarianceStamped>("mcl_measurement", 1, true);
94 
95  ros::Duration(1.0).sleep();
96  pub_init.publish(generatePoseWithCov(2.0, 1.0));
97  ros::Duration(0.1).sleep();
98  ros::spinOnce();
99 
100  ASSERT_TRUE(static_cast<bool>(poses));
101  for (const geometry_msgs::Pose p : poses->poses)
102  {
103  ASSERT_FLOAT_EQ(p.position.x, 0.0f);
104  ASSERT_FLOAT_EQ(p.position.z, 0.0f);
105  ASSERT_FLOAT_EQ(p.orientation.x, 0.0f);
106  ASSERT_FLOAT_EQ(p.orientation.y, 0.0f);
107  ASSERT_FLOAT_EQ(p.orientation.z, 0.0f);
108  ASSERT_FLOAT_EQ(p.orientation.w, 1.0f);
109  }
110  const std::pair<float, float> mean_init = getMean(poses->poses);
111  ASSERT_NEAR(mean_init.first, 2.0f, 0.1f);
112  ASSERT_NEAR(mean_init.second, 1.0f, 0.1f);
113 
114  poses = nullptr;
115  pub_landmark.publish(generatePoseWithCov(2.6, 1.0, 1000.0));
116  ros::Duration(0.1).sleep();
117  ros::spinOnce();
118 
119  ASSERT_TRUE(static_cast<bool>(poses));
120  for (const geometry_msgs::Pose p : poses->poses)
121  {
122  ASSERT_FLOAT_EQ(p.position.x, 0.0f);
123  ASSERT_FLOAT_EQ(p.position.z, 0.0f);
124  ASSERT_FLOAT_EQ(p.orientation.x, 0.0f);
125  ASSERT_FLOAT_EQ(p.orientation.y, 0.0f);
126  ASSERT_FLOAT_EQ(p.orientation.z, 0.0f);
127  ASSERT_FLOAT_EQ(p.orientation.w, 1.0f);
128  }
129  const std::pair<float, float> mean_measured = getMean(poses->poses);
130  ASSERT_NEAR(mean_measured.first, 2.3f, 0.1f);
131  ASSERT_NEAR(mean_measured.second, 0.5f, 0.1f);
132 }
133 
134 int main(int argc, char** argv)
135 {
136  testing::InitGoogleTest(&argc, argv);
137  ros::init(argc, argv, "test_landmark");
138 
139  return RUN_ALL_TESTS();
140 }
void publish(const boost::shared_ptr< M > &message) const
TEST(Landmark, Measurement)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static Time now()
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36