rosout_appender.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #include "ros/rosout_appender.h"
00036 #include "ros/this_node.h"
00037 #include "ros/node_handle.h"
00038 #include "ros/topic_manager.h"
00039 #include "ros/advertise_options.h"
00040 #include "ros/names.h"
00041 
00042 #include <log4cxx/spi/loggingevent.h>
00043 #ifdef _MSC_VER
00044   #include "log4cxx/helpers/transcoder.h" // Have to be able to encode wchar LogStrings on windows.
00045 #endif
00046 
00047 #ifdef WIN32
00048   #ifdef ERROR
00049     // ach, windows.h polluting everything again,
00050         // clashes with autogenerated rosgraph_msgs/Log.h
00051     #undef ERROR
00052   #endif
00053 #endif
00054 #include <rosgraph_msgs/Log.h>
00055 
00056 namespace ros
00057 {
00058 
00059 ROSOutAppender::ROSOutAppender()
00060 : shutting_down_(false)
00061 , publish_thread_(boost::bind(&ROSOutAppender::logThread, this))
00062 {
00063   AdvertiseOptions ops;
00064   ops.init<rosgraph_msgs::Log>(names::resolve("/rosout"), 0);
00065   ops.latch = true;
00066   SubscriberCallbacksPtr cbs(new SubscriberCallbacks);
00067   TopicManager::instance()->advertise(ops, cbs);
00068 }
00069 
00070 ROSOutAppender::~ROSOutAppender()
00071 {
00072   shutting_down_ = true;
00073 
00074   {
00075     boost::mutex::scoped_lock lock(queue_mutex_);
00076     queue_condition_.notify_all();
00077   }
00078 
00079   publish_thread_.join();
00080 }
00081 
00082 const std::string&  ROSOutAppender::getLastError()
00083 {
00084   return last_error_;
00085 }
00086 
00087 void ROSOutAppender::append(const log4cxx::spi::LoggingEventPtr& event, log4cxx::helpers::Pool& pool)
00088 {
00089   rosgraph_msgs::LogPtr msg(new rosgraph_msgs::Log);
00090 
00091   msg->header.stamp = ros::Time::now();
00092 
00093   if (event->getLevel() == log4cxx::Level::getFatal())
00094   {
00095     msg->level = rosgraph_msgs::Log::FATAL;
00096     #ifdef _MSC_VER
00097       LOG4CXX_ENCODE_CHAR(tmpstr, event->getMessage()); // has to handle LogString with wchar types.
00098       last_error_ = tmpstr; // tmpstr gets instantiated inside the LOG4CXX_ENCODE_CHAR macro
00099     #else
00100     last_error_ = event->getMessage();
00101     #endif
00102 
00103   }
00104   else if (event->getLevel() == log4cxx::Level::getError())
00105   {
00106     msg->level = rosgraph_msgs::Log::ERROR;
00107     #ifdef _MSC_VER
00108       LOG4CXX_ENCODE_CHAR(tmpstr, event->getMessage()); // has to handle LogString with wchar types.
00109       last_error_ = tmpstr; // tmpstr gets instantiated inside the LOG4CXX_ENCODE_CHAR macro
00110     #else
00111     last_error_ = event->getMessage();
00112     #endif
00113   }
00114   else if (event->getLevel() == log4cxx::Level::getWarn())
00115   {
00116     msg->level = rosgraph_msgs::Log::WARN;
00117   }
00118   else if (event->getLevel() == log4cxx::Level::getInfo())
00119   {
00120     msg->level = rosgraph_msgs::Log::INFO;
00121   }
00122   else if (event->getLevel() == log4cxx::Level::getDebug())
00123   {
00124     msg->level = rosgraph_msgs::Log::DEBUG;
00125   }
00126 
00127   msg->name = this_node::getName();
00128   #ifdef _MSC_VER
00129     LOG4CXX_ENCODE_CHAR(tmpstr, event->getMessage()); // has to handle LogString with wchar types.
00130     msg->msg = tmpstr; // tmpstr gets instantiated inside the LOG4CXX_ENCODE_CHAR macro
00131   #else
00132   msg->msg = event->getMessage();
00133   #endif
00134 
00135   const log4cxx::spi::LocationInfo& info = event->getLocationInformation();
00136   msg->file = info.getFileName();
00137   msg->function = info.getMethodName();
00138   msg->line = info.getLineNumber();
00139 
00140   this_node::getAdvertisedTopics(msg->topics);
00141 
00142   boost::mutex::scoped_lock lock(queue_mutex_);
00143   log_queue_.push_back(msg);
00144   queue_condition_.notify_all();
00145 }
00146 
00147 void ROSOutAppender::logThread()
00148 {
00149   while (!shutting_down_)
00150   {
00151     V_Log local_queue;
00152 
00153     {
00154       boost::mutex::scoped_lock lock(queue_mutex_);
00155 
00156       if (shutting_down_)
00157       {
00158         return;
00159       }
00160 
00161       queue_condition_.wait(lock);
00162 
00163       if (shutting_down_)
00164       {
00165         return;
00166       }
00167 
00168       local_queue.swap(log_queue_);
00169     }
00170 
00171     V_Log::iterator it = local_queue.begin();
00172     V_Log::iterator end = local_queue.end();
00173     for (; it != end; ++it)
00174     {
00175       TopicManager::instance()->publish(names::resolve("/rosout"), *(*it));
00176     }
00177   }
00178 }
00179 
00180 } // namespace ros


roscpp
Author(s): Morgan Quigley mquigley@cs.stanford.edu, Josh Faust jfaust@willowgarage.com, Brian Gerkey gerkey@willowgarage.com, Troy Straszheim straszheim@willowgarage.com
autogenerated on Sat Dec 28 2013 17:35:52