37 #include <geometry_msgs/PoseWithCovarianceStamped.h>
38 #include <nav_msgs/Odometry.h>
39 #include <sensor_msgs/Imu.h>
40 #include <sensor_msgs/PointCloud2.h>
45 #include <gtest/gtest.h>
49 void generateSamplePointcloud2(
50 sensor_msgs::PointCloud2& cloud,
57 cloud.is_bigendian =
false;
58 cloud.is_dense =
false;
60 modifier.setPointCloud2Fields(
62 "x", 1, sensor_msgs::PointField::FLOAT32,
63 "y", 1, sensor_msgs::PointField::FLOAT32,
64 "z", 1, sensor_msgs::PointField::FLOAT32,
65 "label", 1, sensor_msgs::PointField::UINT32);
67 const float resolution = 0.05;
69 std::vector<Eigen::Vector4d> points;
71 for (
float x = -range; x < range; x += resolution)
73 for (
float y = -range; y < range; y += resolution)
75 points.emplace_back(x, y, -1.0, 0);
79 for (
float x = -0.5; x < 0.5; x += resolution)
81 for (
float z = -1.0; z < 0.0; z += resolution)
83 points.emplace_back(x, 1.0, z, 2);
87 modifier.resize(points.size());
88 cloud.width = points.size();
94 for (
const Eigen::Vector4d& p : points)
96 *iter_x = p[0] + offset_x;
97 *iter_y = p[1] + offset_y;
98 *iter_z = p[2] + offset_z;
99 *iter_label =
static_cast<uint32_t
>(p[3]);
107 inline sensor_msgs::PointCloud2 generateMapMsg(
108 const float offset_x,
109 const float offset_y,
110 const float offset_z)
112 sensor_msgs::PointCloud2 cloud;
113 generateSamplePointcloud2(cloud, offset_x, offset_y, offset_z, 5.0);
114 cloud.header.frame_id =
"map";
117 inline sensor_msgs::PointCloud2 generateCloudMsg()
119 sensor_msgs::PointCloud2 cloud;
120 generateSamplePointcloud2(cloud, 0, 0, 0, 2.0);
121 cloud.header.frame_id =
"base_link";
125 inline sensor_msgs::Imu generateImuMsg()
127 sensor_msgs::Imu imu;
128 imu.header.frame_id =
"base_link";
130 imu.orientation.w = 1;
131 imu.linear_acceleration.z = 9.8;
134 inline nav_msgs::Odometry generateOdomMsg()
136 nav_msgs::Odometry odom;
137 odom.header.frame_id =
"odom";
139 odom.pose.pose.position.x = 1;
140 odom.pose.pose.orientation.w = 1;
143 inline geometry_msgs::PoseWithCovarianceStamped generateInitialPose()
145 geometry_msgs::PoseWithCovarianceStamped pose;
146 pose.header.frame_id =
"map";
148 pose.pose.pose.orientation.w = 1.0;
149 pose.pose.covariance[6 * 0 + 0] = std::pow(0.2, 2);
150 pose.pose.covariance[6 * 1 + 1] = std::pow(0.2, 2);
151 pose.pose.covariance[6 * 2 + 2] = std::pow(0.2, 2);
152 pose.pose.covariance[6 * 3 + 3] = 0.0;
153 pose.pose.covariance[6 * 4 + 4] = 0.0;
154 pose.pose.covariance[6 * 5 + 5] = std::pow(0.05, 2);
170 geometry_msgs::PoseWithCovarianceStamped::ConstPtr
pose_cov_;
172 void cbPoseCov(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
181 for (
int i = 0; i < 100; i++)
202 nh_.
advertise<geometry_msgs::PoseWithCovarianceStamped>(
"initialpose", 1,
true);
208 const float offset_x = 0.05;
209 const float offset_y = 0.05;
210 const float offset_z = 0;
211 pub_mapcloud_.publish(generateMapMsg(offset_x, offset_y, offset_z));
215 for (
int i = 0; i < 100; ++i)
219 pub_cloud_.publish(generateCloudMsg());
220 pub_imu_.publish(generateImuMsg());
221 pub_odom_.publish(generateOdomMsg());
225 ASSERT_TRUE(
static_cast<bool>(pose_cov_));
227 ASSERT_NEAR(pose_cov_->pose.pose.position.x, offset_x, 0.1);
228 ASSERT_NEAR(pose_cov_->pose.pose.position.y, offset_y, 0.1);
229 ASSERT_NEAR(pose_cov_->pose.pose.position.z, offset_z, 0.1);
232 int main(
int argc,
char** argv)
234 testing::InitGoogleTest(&argc, argv);
235 ros::init(argc, argv,
"test_beam_label");
238 return RUN_ALL_TESTS();