32 #include <nav_msgs/Odometry.h>
33 #include <sensor_msgs/Imu.h>
34 #include <sensor_msgs/PointCloud2.h>
36 #include <std_srvs/Trigger.h>
43 #include <gtest/gtest.h>
47 void generateSamplePointcloud2(
48 sensor_msgs::PointCloud2& cloud,
54 cloud.is_bigendian =
false;
55 cloud.is_dense =
false;
57 modifier.setPointCloud2Fields(
59 "x", 1, sensor_msgs::PointField::FLOAT32,
60 "y", 1, sensor_msgs::PointField::FLOAT32,
61 "z", 1, sensor_msgs::PointField::FLOAT32,
62 "intensity", 1, sensor_msgs::PointField::FLOAT32);
68 Point(
const float x,
const float y,
const float z)
75 std::vector<Point> points;
77 for (
float x = -1; x < 1; x += 0.05)
79 for (
float y = -1; y < 1; y += 0.05)
81 points.push_back(
Point(1.0 / 2 + offset_x, y + offset_y, x + offset_z));
82 points.push_back(
Point(-1.0 / 2 + offset_x, y + offset_y, x + offset_z));
86 modifier.resize(points.size());
87 cloud.width = points.size();
92 for (
const Point& p : points)
103 inline sensor_msgs::PointCloud2 generateMapMsg(
104 const float offset_x,
105 const float offset_y,
106 const float offset_z)
108 sensor_msgs::PointCloud2 cloud;
109 generateSamplePointcloud2(cloud, offset_x, offset_y, offset_z);
110 cloud.header.frame_id =
"map";
113 inline sensor_msgs::PointCloud2 generateCloudMsg()
115 sensor_msgs::PointCloud2 cloud;
116 generateSamplePointcloud2(cloud, 0, 0, 0);
117 cloud.header.frame_id =
"base_link";
121 inline sensor_msgs::Imu generateImuMsg()
123 sensor_msgs::Imu imu;
124 imu.header.frame_id =
"base_link";
126 imu.orientation.w = 1;
127 imu.linear_acceleration.z = 9.8;
130 inline nav_msgs::Odometry generateOdomMsg()
132 nav_msgs::Odometry odom;
133 odom.header.frame_id =
"odom";
135 odom.pose.pose.position.x = 1;
136 odom.pose.pose.orientation.w = 1;
141 TEST(DebugOutput, MatchedUnmatched)
143 sensor_msgs::PointCloud2::ConstPtr matched, unmatched;
145 const boost::function<void(
const sensor_msgs::PointCloud2::ConstPtr&)> cb_matched =
146 [&matched](
const sensor_msgs::PointCloud2::ConstPtr&
msg) ->
void
150 const boost::function<void(
const sensor_msgs::PointCloud2::ConstPtr&)> cb_unmatched =
151 [&unmatched](
const sensor_msgs::PointCloud2::ConstPtr&
msg) ->
void
165 const float offset_x = 1;
166 const float offset_y = 0;
167 const float offset_z = 0;
168 pub_mapcloud.
publish(generateMapMsg(offset_x, offset_y, offset_z));
172 for (
int i = 0; i < 40; ++i)
176 if (matched && unmatched)
178 pub_cloud.publish(generateCloudMsg());
179 pub_imu.publish(generateImuMsg());
180 pub_odom.publish(generateOdomMsg());
184 ASSERT_TRUE(
static_cast<bool>(matched));
185 ASSERT_TRUE(
static_cast<bool>(unmatched));
187 ASSERT_GT(matched->width * matched->height, 0u);
188 ASSERT_GT(unmatched->width * unmatched->height, 0u);
194 for (; x != x.
end(); ++x, ++y, ++z)
196 ASSERT_NEAR(*x, 0.5
f, 0.1
f);
197 ASSERT_TRUE(-1.1 < *y && *y < 1.1);
198 ASSERT_TRUE(-1.1 < *z && *z < 1.1);
205 for (; x != x.
end(); ++x, ++y, ++z)
207 ASSERT_NEAR(*x, -0.5
f, 0.1
f);
208 ASSERT_TRUE(-1.1 < *y && *y < 1.1);
209 ASSERT_TRUE(-1.1 < *z && *z < 1.1);
214 int main(
int argc,
char** argv)
216 testing::InitGoogleTest(&argc, argv);
217 ros::init(argc, argv,
"test_debug_output");
219 return RUN_ALL_TESTS();