32 #include <geometry_msgs/PoseArray.h> 33 #include <mcl_3dl_msgs/Status.h> 34 #include <nav_msgs/Odometry.h> 35 #include <sensor_msgs/Imu.h> 36 #include <sensor_msgs/PointCloud2.h> 38 #include <std_srvs/Trigger.h> 45 #include <gtest/gtest.h> 49 void generateSamplePointcloud2(
50 sensor_msgs::PointCloud2& cloud,
58 const float offset_yaw)
60 std::random_device seed;
61 std::default_random_engine engine(seed());
62 std::normal_distribution<float> rand(0, 0.01);
65 cloud.is_bigendian =
false;
66 cloud.is_dense =
false;
68 modifier.setPointCloud2Fields(
70 "x", 1, sensor_msgs::PointField::FLOAT32,
71 "y", 1, sensor_msgs::PointField::FLOAT32,
72 "z", 1, sensor_msgs::PointField::FLOAT32,
73 "intensity", 1, sensor_msgs::PointField::FLOAT32);
79 Point(
const float x,
const float y,
const float z)
86 std::vector<Point> points;
87 const float grid_xy = 0.15;
88 const float grid_z = 0.1;
89 const float floor_size = 6.0;
91 for (
float x = -floor_size;
x < floor_size;
x += grid_xy)
92 for (
float y = -floor_size;
y < floor_size;
y += grid_xy)
93 if (x0 <
x &&
x < x1 && y0 <
y &&
y < y1)
94 points.push_back(
Point(
x,
y, 0.0));
96 for (
float x = -2;
x < 1.6;
x += grid_xy)
98 for (
float z = 0.5;
z < 1.5;
z += grid_z)
99 points.push_back(
Point(
x, 1.6,
z));
100 for (
float y = -0.5;
y < 1.6;
y += grid_xy)
101 if (y0 <
y &&
y < y1)
102 for (
float z = 0.5;
z < 2.0;
z += grid_z)
103 points.push_back(
Point(1.6,
y,
z));
104 for (
float x = 0;
x < 1.6;
x += grid_xy)
105 if (x0 <
x &&
x < x1)
106 for (
float z = 0.5;
z < 2.0;
z += grid_z)
107 points.push_back(
Point(
x, -2.1 +
x,
z));
109 const float o_cos = cosf(offset_yaw);
110 const float o_sin = sinf(offset_yaw);
111 modifier.resize(points.size());
112 cloud.width = points.size();
117 for (
const Point& p : points)
119 *iter_x = p.x_ * o_cos - p.y_ * o_sin + offset_x + rand(engine);
120 *iter_y = p.x_ * o_sin + p.y_ * o_cos + offset_y + rand(engine);
121 *iter_z = p.z_ + offset_z + rand(engine);
128 inline sensor_msgs::PointCloud2 generateMapMsg()
130 sensor_msgs::PointCloud2 cloud;
131 generateSamplePointcloud2(cloud, -100, -100, 100, 100, 0, 0, 0, 0);
132 cloud.header.frame_id =
"map";
135 inline sensor_msgs::PointCloud2 generateCloudMsg(
136 const float offset_x,
137 const float offset_y,
138 const float offset_z,
139 const float offset_yaw)
141 sensor_msgs::PointCloud2 cloud;
142 generateSamplePointcloud2(
144 offset_x, offset_y, offset_z, offset_yaw);
145 cloud.header.frame_id =
"laser";
149 inline sensor_msgs::Imu generateImuMsg()
151 sensor_msgs::Imu imu;
152 imu.header.frame_id =
"base_link";
154 imu.orientation.w = 1;
155 imu.linear_acceleration.z = 9.8;
158 inline nav_msgs::Odometry generateOdomMsg()
160 nav_msgs::Odometry odom;
161 odom.header.frame_id =
"odom";
163 odom.pose.pose.position.y = 5;
164 odom.pose.pose.orientation.w = 1;
169 TEST(GlobalLocalization, Localize)
171 geometry_msgs::PoseArray::ConstPtr poses;
172 mcl_3dl_msgs::Status::ConstPtr status;
174 const boost::function<void(const geometry_msgs::PoseArray::ConstPtr&)> cb_pose =
175 [&poses](
const geometry_msgs::PoseArray::ConstPtr& msg) ->
void 179 const boost::function<void(const mcl_3dl_msgs::Status::ConstPtr&)> cb_status =
180 [&status](
const mcl_3dl_msgs::Status::ConstPtr& msg) ->
void 190 nh.
serviceClient<std_srvs::TriggerRequest, std_srvs::TriggerResponse>(
191 "global_localization");
198 pub_mapcloud.
publish(generateMapMsg());
200 for (
float offset_x = -0.5; offset_x <= 0.51; offset_x += 1.0)
202 for (
float offset_yaw = -M_PI / 2; offset_yaw <= M_PI / 2 + 0.1; offset_yaw += M_PI)
204 const float laser_frame_height = 0.5;
205 const float offset_y = 0.54;
206 const float offset_z = 0.0;
214 if (status && status->status == mcl_3dl_msgs::Status::NORMAL)
217 generateCloudMsg(offset_x, offset_y, offset_z - laser_frame_height, offset_yaw));
218 pub_imu.publish(generateImuMsg());
219 pub_odom.publish(generateOdomMsg());
223 std_srvs::Trigger trigger;
224 ASSERT_TRUE(src_global_localization.
call(trigger));
232 if (status && status->status == mcl_3dl_msgs::Status::GLOBAL_LOCALIZATION)
235 generateCloudMsg(offset_x, offset_y, offset_z - laser_frame_height, offset_yaw));
236 pub_imu.publish(generateImuMsg());
237 pub_odom.publish(generateOdomMsg());
246 if (status && status->status == mcl_3dl_msgs::Status::NORMAL)
249 generateCloudMsg(offset_x, offset_y, offset_z - laser_frame_height, offset_yaw));
250 pub_imu.publish(generateImuMsg());
251 pub_odom.publish(generateOdomMsg());
256 for (
int i = 0; i < 40; ++i)
261 generateCloudMsg(offset_x, offset_y, offset_z - laser_frame_height, offset_yaw));
262 pub_imu.publish(generateImuMsg());
263 pub_odom.publish(generateOdomMsg());
267 ASSERT_TRUE(static_cast<bool>(status));
268 ASSERT_TRUE(static_cast<bool>(poses));
273 -(offset_x *
cos(-offset_yaw) - offset_y *
sin(-offset_yaw)),
274 -(offset_x *
sin(-offset_yaw) + offset_y *
cos(-offset_yaw)),
276 bool found_true_positive(
false);
277 for (
const auto& pose : poses->poses)
283 if (tf_diff.
getOrigin().length() < 2e-1 &&
285 found_true_positive =
true;
287 ASSERT_TRUE(found_true_positive);
292 int main(
int argc,
char** argv)
294 testing::InitGoogleTest(&argc, argv);
295 ros::init(argc, argv,
"test_global_localization");
297 return RUN_ALL_TESTS();
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
TEST(GlobalLocalization, Localize)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
TFSIMD_FORCE_INLINE const tfScalar & x() const
int main(int argc, char **argv)
TFSIMD_FORCE_INLINE const tfScalar & z() const
void fromMsg(const A &, B &b)
TFSIMD_FORCE_INLINE const tfScalar & y() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double getYaw(const A &a)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
ROSCPP_DECL void spinOnce()
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)