service_exception.cpp
Go to the documentation of this file.
1 #include <cstdlib>
2 #include <gtest/gtest.h>
3 #include <list>
4 
5 #include "ros/ros.h"
6 #include "std_srvs/Empty.h"
7 #include <log4cxx/appenderskeleton.h>
8 #include <ros/console.h>
9 #include <ros/poll_manager.h>
10 
11 class ListAppender : public log4cxx::AppenderSkeleton
12 {
13 public:
14  void append(const log4cxx::spi::LoggingEventPtr& event, log4cxx::helpers::Pool&)
15  {
16  list.push_back(event);
17  }
18 
19  void close()
20  {
21  this->closed = true;
22  }
23 
24  bool isClosed() const
25  {
26  return closed;
27  }
28 
29  bool requiresLayout() const
30  {
31  return false;
32  }
33 
34  const std::list<log4cxx::spi::LoggingEventPtr>& getList() const
35  {
36  return list;
37  }
38 
39 protected:
40  std::list<log4cxx::spi::LoggingEventPtr> list;
41 };
42 typedef log4cxx::helpers::ObjectPtrT<ListAppender> ListAppenderPtr;
43 
44 static const char EXCEPTION[] = "custom exception message";
45 
46 bool throwingService(std_srvs::Empty::Request&, std_srvs::Empty::Request&)
47 {
48  throw std::runtime_error(EXCEPTION);
49  return true;
50 }
51 
52 static const char SERVICE[] = "service_exception";
53 
54 TEST(roscpp, ServiceThrowingException)
55 {
56  ros::AsyncSpinner spinner(1);
57  spinner.start();
58 
61 
62  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger("ros.roscpp");
63  ListAppenderPtr appender = new ListAppender();
64  logger->addAppender(appender);
65 
66  ros::ServiceClient client = n.serviceClient<std_srvs::Empty>(SERVICE, true);
67  std_srvs::Empty srv;
68  bool success = client.call(srv);
69  ASSERT_FALSE(success);
70 
71  bool found_error_output = false;
72  const std::list<log4cxx::spi::LoggingEventPtr>& list = appender->getList();
73  for (std::list<log4cxx::spi::LoggingEventPtr>::const_iterator it = list.begin(); it != list.end(); it++)
74  {
75  const log4cxx::LogString& msg = (*it)->getMessage();
76  size_t pos_error = msg.find("Service call failed:");
77  size_t pos_exception = msg.find(EXCEPTION);
78  if (pos_error != std::string::npos && pos_exception != std::string::npos)
79  {
80  found_error_output = true;
81  }
82  }
83  ASSERT_TRUE(found_error_output);
84 }
85 
86 int main(int argc, char **argv)
87 {
88  testing::InitGoogleTest(&argc, argv);
89  ros::init(argc, argv, "service_exception");
90  return RUN_ALL_TESTS();
91 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
static const char EXCEPTION[]
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool throwingService(std_srvs::Empty::Request &, std_srvs::Empty::Request &)
bool call(MReq &req, MRes &res)
std::list< log4cxx::spi::LoggingEventPtr > list
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool requiresLayout() const
bool isClosed() const
const std::list< log4cxx::spi::LoggingEventPtr > & getList() const
log4cxx::helpers::ObjectPtrT< ListAppender > ListAppenderPtr
static const char SERVICE[]
void append(const log4cxx::spi::LoggingEventPtr &event, log4cxx::helpers::Pool &)
int main(int argc, char **argv)
TEST(roscpp, ServiceThrowingException)


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:46