32 #include <nav_msgs/OccupancyGrid.h>
33 #include <nav_msgs/Path.h>
34 #include <neonavigation_metrics_msgs/Metrics.h>
35 #include <planner_cspace_msgs/PlannerStatus.h>
36 #include <sensor_msgs/PointCloud.h>
38 #include <gtest/gtest.h>
81 void showMap(
const nav_msgs::OccupancyGrid::ConstPtr& msg)
83 std::cerr << std::hex;
84 for (
size_t y = 0; y <
msg->info.height; ++y)
86 for (
size_t x = 0; x <
msg->info.width; ++x)
88 std::cerr << (
msg->data[x + y *
msg->info.width] / 11);
90 std::cerr << std::endl;
92 std::cerr << std::dec;
94 std::streamsize ss = std::cerr.precision();
95 std::cerr <<
"path:" << std::endl
96 << std::setprecision(3);
97 for (
const auto& p :
path_->poses)
98 std::cerr << p.pose.position.x <<
", " << p.pose.position.y <<
", " << std::endl;
100 std::cerr << std::setprecision(ss);
114 void cbDistance(
const sensor_msgs::PointCloud::ConstPtr& msg)
119 void cbStatus(
const planner_cspace_msgs::PlannerStatus::ConstPtr& msg)
121 if (
msg->error == planner_cspace_msgs::PlannerStatus::GOING_WELL &&
122 msg->status == planner_cspace_msgs::PlannerStatus::DOING)
125 void cbMetrics(
const neonavigation_metrics_msgs::Metrics::ConstPtr& msg)
129 void cbPath(
const nav_msgs::Path::ConstPtr& msg)
131 if (
msg->poses.size() > 0)
143 neonavigation_metrics_msgs::Metrics::ConstPtr
metrics_;
166 ASSERT_TRUE(
static_cast<bool>(map_hysteresis_));
184 for (
auto data : data_set)
186 const size_t addr =
data.x +
data.y * map_hysteresis_->info.width;
187 EXPECT_EQ(
data.value, map_hysteresis_->data[addr]) <<
"x: " <<
data.x <<
", y: " <<
data.y;
189 if (::testing::Test::HasFailure())
191 showMap(map_hysteresis_);
197 ASSERT_TRUE(
static_cast<bool>(map_remembered_));
211 for (
auto data : data_set)
213 const size_t addr =
data.x +
data.y * map_remembered_->info.width;
214 EXPECT_EQ(
data.value, map_remembered_->data[addr]) <<
"x: " <<
data.x <<
", y: " <<
data.y;
216 if (::testing::Test::HasFailure())
218 showMap(map_remembered_);
224 ASSERT_TRUE(
static_cast<bool>(map_distance_));
227 for (
size_t i = 0; i < map_distance_->points.size(); ++i)
229 const float x = map_distance_->points[i].x;
230 const float y = map_distance_->points[i].y;
231 const float d = map_distance_->channels[0].values[i];
232 if (std::abs(y - 0.5) < 0.05)
234 const float dist_from_goal = std::abs(x - 1.0);
235 ASSERT_NEAR(dist_from_goal,
d, 0.15);
245 ASSERT_TRUE(metrics_);
246 ASSERT_NE(0u, metrics_->data.size());
249 int main(
int argc,
char** argv)
251 testing::InitGoogleTest(&argc, argv);
252 ros::init(argc, argv,
"test_debug_outputs");
254 return RUN_ALL_TESTS();