test_costmap_watchdog.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <string>
31 
32 #include <ros/ros.h>
33 
34 #include <diagnostic_msgs/DiagnosticArray.h>
35 #include <geometry_msgs/PoseStamped.h>
36 #include <nav_msgs/Path.h>
37 
38 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
39 #include <planner_cspace_msgs/PlannerStatus.h>
40 
41 #include <gtest/gtest.h>
42 
43 TEST(Planner3D, CostmapWatchdog)
44 {
45  int cnt = 0;
46  planner_cspace_msgs::PlannerStatus::ConstPtr status;
47  nav_msgs::Path::ConstPtr path;
48  diagnostic_msgs::DiagnosticArray::ConstPtr diag;
49 
50  const boost::function<void(const planner_cspace_msgs::PlannerStatus::ConstPtr&)> cb_status =
51  [&status, &cnt](const planner_cspace_msgs::PlannerStatus::ConstPtr& msg) -> void
52  {
53  status = msg;
54  cnt++;
55  };
56  const boost::function<void(const nav_msgs::Path::ConstPtr&)> cb_path =
57  [&path](const nav_msgs::Path::ConstPtr& msg) -> void
58  {
59  path = msg;
60  };
61  const boost::function<void(const diagnostic_msgs::DiagnosticArray::ConstPtr&)> cb_diag =
62  [&diag](const diagnostic_msgs::DiagnosticArray::ConstPtr& msg) -> void
63  {
64  diag = msg;
65  };
66 
67  ros::NodeHandle nh("");
68  ros::Publisher pub_goal = nh.advertise<geometry_msgs::PoseStamped>("goal", 1, true);
69  ros::Publisher pub_cost_update = nh.advertise<costmap_cspace_msgs::CSpace3DUpdate>("costmap_update", 1);
70  ros::Subscriber sub_status = nh.subscribe("planner_3d/status", 1, cb_status);
71  ros::Subscriber sub_path = nh.subscribe("path", 1, cb_path);
72  ros::Subscriber sub_diag = nh.subscribe("diagnostics", 1, cb_diag);
73 
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;
79  pub_goal.publish(goal);
80 
81  ros::Rate rate(10);
82  while (ros::ok())
83  {
84  // cnt increments in 5 Hz at maximum
85  if (cnt == 0 || cnt > 8)
86  {
87  costmap_cspace_msgs::CSpace3DUpdate update;
88  update.header.stamp = ros::Time::now();
89  update.header.frame_id = "map";
90  update.width = update.height = update.angle = 0;
91  pub_cost_update.publish(update);
92  }
93 
94  ros::spinOnce();
95  rate.sleep();
96 
97  if (!status)
98  continue;
99 
100  if (5 < cnt && cnt < 8)
101  {
102  ASSERT_EQ(status->error, planner_cspace_msgs::PlannerStatus::DATA_MISSING);
103 
104  ASSERT_TRUE(static_cast<bool>(path));
105  ASSERT_EQ(path->poses.size(), 0u);
106 
107  ASSERT_TRUE(static_cast<bool>(diag));
108  ASSERT_EQ(diag->status.size(), 1u);
109  ASSERT_EQ(diag->status[0].level, diagnostic_msgs::DiagnosticStatus::ERROR);
110  ASSERT_NE(diag->status[0].message.find("missing"), std::string::npos);
111  }
112  else if (10 < cnt && cnt < 13)
113  {
114  ASSERT_EQ(status->status, planner_cspace_msgs::PlannerStatus::DOING);
115  ASSERT_EQ(status->error, planner_cspace_msgs::PlannerStatus::GOING_WELL);
116 
117  ASSERT_EQ(diag->status.size(), 1u);
118  ASSERT_EQ(diag->status[0].level, diagnostic_msgs::DiagnosticStatus::OK);
119  ASSERT_NE(diag->status[0].message.find("well"), std::string::npos);
120  }
121  else if (cnt >= 13)
122  {
123  return;
124  }
125  }
126  ASSERT_TRUE(ros::ok());
127 }
128 
129 int main(int argc, char** argv)
130 {
131  testing::InitGoogleTest(&argc, argv);
132  ros::init(argc, argv, "test_navigate");
133 
134  return RUN_ALL_TESTS();
135 }
TEST(Planner3D, CostmapWatchdog)
msg
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())
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)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
int main(int argc, char **argv)
static Time now()
ROSCPP_DECL void spinOnce()


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:13