2 #include <gtest/gtest.h> 6 #include "std_srvs/Empty.h" 7 #include <log4cxx/appenderskeleton.h> 14 void append(
const log4cxx::spi::LoggingEventPtr& event, log4cxx::helpers::Pool&)
16 list.push_back(event);
34 const std::list<log4cxx::spi::LoggingEventPtr>&
getList()
const 40 std::list<log4cxx::spi::LoggingEventPtr>
list;
44 static const char EXCEPTION[] =
"custom exception message";
52 static const char SERVICE[] =
"service_exception";
62 log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(
"ros.roscpp");
64 logger->addAppender(appender);
68 bool success = client.
call(srv);
69 ASSERT_FALSE(success);
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++)
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)
80 found_error_output =
true;
83 ASSERT_TRUE(found_error_output);
86 int main(
int argc,
char **argv)
88 testing::InitGoogleTest(&argc, argv);
89 ros::init(argc, argv,
"service_exception");
90 return RUN_ALL_TESTS();
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
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)