34 #include <diagnostic_msgs/DiagnosticArray.h> 35 #include <geometry_msgs/PoseStamped.h> 36 #include <nav_msgs/Path.h> 38 #include <costmap_cspace_msgs/CSpace3DUpdate.h> 39 #include <planner_cspace_msgs/PlannerStatus.h> 41 #include <gtest/gtest.h> 43 TEST(Planner3D, CostmapWatchdog)
46 planner_cspace_msgs::PlannerStatus::ConstPtr status;
47 nav_msgs::Path::ConstPtr path;
48 diagnostic_msgs::DiagnosticArray::ConstPtr diag;
50 const boost::function<void(const planner_cspace_msgs::PlannerStatus::ConstPtr&)> cb_status =
51 [&status, &cnt](
const planner_cspace_msgs::PlannerStatus::ConstPtr&
msg) ->
void 56 const boost::function<void(const nav_msgs::Path::ConstPtr&)> cb_path =
57 [&path](
const nav_msgs::Path::ConstPtr&
msg) ->
void 61 const boost::function<void(const diagnostic_msgs::DiagnosticArray::ConstPtr&)> cb_diag =
62 [&diag](
const diagnostic_msgs::DiagnosticArray::ConstPtr&
msg) ->
void 74 geometry_msgs::PoseStamped goal;
75 goal.header.frame_id =
"map";
76 goal.pose.position.x = 1.9;
77 goal.pose.position.y = 2.8;
78 goal.pose.orientation.w = 1.0;
87 if (cnt == 0 || cnt > 8)
89 costmap_cspace_msgs::CSpace3DUpdate
update;
91 update.header.frame_id =
"map";
92 update.width = update.height = update.angle = 0;
93 pub_cost_update.publish(update);
102 if (5 < cnt && cnt < 8)
104 ASSERT_EQ(status->error, planner_cspace_msgs::PlannerStatus::DATA_MISSING);
106 ASSERT_TRUE(static_cast<bool>(path));
107 ASSERT_EQ(path->poses.size(), 0u);
109 ASSERT_TRUE(static_cast<bool>(diag));
110 ASSERT_EQ(diag->status.size(), 1u);
111 ASSERT_EQ(diag->status[0].level, diagnostic_msgs::DiagnosticStatus::ERROR);
112 ASSERT_NE(diag->status[0].message.find(
"missing"), std::string::npos);
114 else if (10 < cnt && cnt < 13)
116 ASSERT_EQ(status->status, planner_cspace_msgs::PlannerStatus::DOING);
117 ASSERT_EQ(status->error, planner_cspace_msgs::PlannerStatus::GOING_WELL);
119 ASSERT_EQ(diag->status.size(), 1u);
120 ASSERT_EQ(diag->status[0].level, diagnostic_msgs::DiagnosticStatus::OK);
121 ASSERT_NE(diag->status[0].message.find(
"well"), std::string::npos);
131 TEST(Planner3D, CostmapTimeoutOnFinishing)
133 planner_cspace_msgs::PlannerStatus::ConstPtr status;
134 nav_msgs::Path::ConstPtr path;
136 const boost::function<void(const planner_cspace_msgs::PlannerStatus::ConstPtr&)> cb_status =
137 [&status](
const planner_cspace_msgs::PlannerStatus::ConstPtr&
msg) ->
void 141 const boost::function<void(const nav_msgs::Path::ConstPtr&)> cb_path =
142 [&path](
const nav_msgs::Path::ConstPtr&
msg) ->
void 153 geometry_msgs::PoseStamped goal;
154 goal.header.frame_id =
"map";
155 goal.pose.position.x = 2.55;
156 goal.pose.position.y = 0.45;
157 goal.pose.orientation.w = std::sin(0.09);
158 goal.pose.orientation.z = std::cos(0.09);
163 costmap_cspace_msgs::CSpace3DUpdate
update;
164 update.header.frame_id =
"map";
165 update.width = update.height = update.angle = 0;
172 pub_cost_update.publish(update);
176 if (status && status->status == planner_cspace_msgs::PlannerStatus::FINISHING)
179 ASSERT_LT(update.header.stamp, deadline)
180 <<
"Planner didn't enter FINISHING state: " 181 << (status ? status->status : -1);
187 if (status->error == planner_cspace_msgs::PlannerStatus::DATA_MISSING)
190 ASSERT_EQ(status->status, planner_cspace_msgs::PlannerStatus::FINISHING)
191 <<
"Wrong test condition";
192 ASSERT_LT(update.header.stamp, deadline)
193 <<
"Planner didn't enter DATA_MISSING state" 200 pub_cost_update.publish(update);
207 ASSERT_EQ(status->status, planner_cspace_msgs::PlannerStatus::FINISHING)
208 <<
"Wrong test condition";
209 ASSERT_LT(update.header.stamp, deadline)
210 <<
"No path was published";
215 int main(
int argc,
char** argv)
217 testing::InitGoogleTest(&argc, argv);
220 return RUN_ALL_TESTS();
TEST(Planner3D, CostmapWatchdog)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()