Go to the documentation of this file.00001 #include <cstdlib>
00002 #include <gtest/gtest.h>
00003 #include <list>
00004
00005 #include "ros/ros.h"
00006 #include "std_srvs/Empty.h"
00007 #include <log4cxx/appenderskeleton.h>
00008 #include <ros/console.h>
00009 #include <ros/poll_manager.h>
00010
00011 class ListAppender : public log4cxx::AppenderSkeleton
00012 {
00013 public:
00014 void append(const log4cxx::spi::LoggingEventPtr& event, log4cxx::helpers::Pool&)
00015 {
00016 list.push_back(event);
00017 }
00018
00019 void close()
00020 {
00021 this->closed = true;
00022 }
00023
00024 bool isClosed() const
00025 {
00026 return closed;
00027 }
00028
00029 bool requiresLayout() const
00030 {
00031 return false;
00032 }
00033
00034 const std::list<log4cxx::spi::LoggingEventPtr>& getList() const
00035 {
00036 return list;
00037 }
00038
00039 protected:
00040 std::list<log4cxx::spi::LoggingEventPtr> list;
00041 };
00042 typedef log4cxx::helpers::ObjectPtrT<ListAppender> ListAppenderPtr;
00043
00044 static const char EXCEPTION[] = "custom exception message";
00045
00046 bool throwingService(std_srvs::Empty::Request&, std_srvs::Empty::Request&)
00047 {
00048 throw std::runtime_error(EXCEPTION);
00049 return true;
00050 }
00051
00052 static const char SERVICE[] = "service_exception";
00053
00054 TEST(roscpp, ServiceThrowingException)
00055 {
00056 ros::AsyncSpinner spinner(1);
00057 spinner.start();
00058
00059 ros::NodeHandle n;
00060 ros::ServiceServer service = n.advertiseService(SERVICE, throwingService);
00061
00062 log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger("ros.roscpp");
00063 ListAppenderPtr appender = new ListAppender();
00064 logger->addAppender(appender);
00065
00066 ros::ServiceClient client = n.serviceClient<std_srvs::Empty>(SERVICE, true);
00067 std_srvs::Empty srv;
00068 bool success = client.call(srv);
00069 ASSERT_FALSE(success);
00070
00071 bool found_error_output = false;
00072 const std::list<log4cxx::spi::LoggingEventPtr>& list = appender->getList();
00073 for (std::list<log4cxx::spi::LoggingEventPtr>::const_iterator it = list.begin(); it != list.end(); it++)
00074 {
00075 const log4cxx::LogString& msg = (*it)->getMessage();
00076 size_t pos_error = msg.find("Service call failed:");
00077 size_t pos_exception = msg.find(EXCEPTION);
00078 if (pos_error != std::string::npos && pos_exception != std::string::npos)
00079 {
00080 found_error_output = true;
00081 }
00082 }
00083 ASSERT_TRUE(found_error_output);
00084 }
00085
00086 int main(int argc, char **argv)
00087 {
00088 testing::InitGoogleTest(&argc, argv);
00089 ros::init(argc, argv, "service_exception");
00090 return RUN_ALL_TESTS();
00091 }