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 <rosgraph_msgs/Log.h>
00043 
00044 namespace ros
00045 {
00046 
00047 ROSOutAppender::ROSOutAppender()
00048 : shutting_down_(false)
00049 , publish_thread_(boost::bind(&ROSOutAppender::logThread, this))
00050 {
00051   AdvertiseOptions ops;
00052   ops.init<rosgraph_msgs::Log>(names::resolve("/rosout"), 0);
00053   ops.latch = true;
00054   SubscriberCallbacksPtr cbs(boost::make_shared<SubscriberCallbacks>());
00055   TopicManager::instance()->advertise(ops, cbs);
00056 }
00057 
00058 ROSOutAppender::~ROSOutAppender()
00059 {
00060   shutting_down_ = true;
00061 
00062   {
00063     boost::mutex::scoped_lock lock(queue_mutex_);
00064     queue_condition_.notify_all();
00065   }
00066 
00067   publish_thread_.join();
00068 }
00069 
00070 const std::string&  ROSOutAppender::getLastError() const
00071 {
00072   return last_error_;
00073 }
00074 
00075 void ROSOutAppender::log(::ros::console::Level level, const char* str, const char* file, const char* function, int line)
00076 {
00077   rosgraph_msgs::LogPtr msg(boost::make_shared<rosgraph_msgs::Log>());
00078 
00079   msg->header.stamp = ros::Time::now();
00080   if (level == ros::console::levels::Debug)
00081   {
00082     msg->level = rosgraph_msgs::Log::DEBUG;
00083   }
00084   else if (level == ros::console::levels::Info)
00085   {
00086     msg->level = rosgraph_msgs::Log::INFO;
00087   }
00088   else if (level == ros::console::levels::Warn)
00089   {
00090     msg->level = rosgraph_msgs::Log::WARN;
00091   }
00092   else if (level == ros::console::levels::Error)
00093   {
00094     msg->level = rosgraph_msgs::Log::ERROR;
00095   }
00096   else if (level == ros::console::levels::Fatal)
00097   {
00098     msg->level = rosgraph_msgs::Log::FATAL;
00099   }
00100   msg->name = this_node::getName();
00101   msg->msg = str;
00102   msg->file = file;
00103   msg->function = function;
00104   msg->line = line;
00105   this_node::getAdvertisedTopics(msg->topics);
00106 
00107   if (level == ::ros::console::levels::Fatal || level == ::ros::console::levels::Error)
00108   {
00109     last_error_ = str;
00110   }
00111 
00112   boost::mutex::scoped_lock lock(queue_mutex_);
00113   log_queue_.push_back(msg);
00114   queue_condition_.notify_all();
00115 }
00116 
00117 void ROSOutAppender::logThread()
00118 {
00119   while (!shutting_down_)
00120   {
00121     V_Log local_queue;
00122 
00123     {
00124       boost::mutex::scoped_lock lock(queue_mutex_);
00125 
00126       if (shutting_down_)
00127       {
00128         return;
00129       }
00130 
00131       queue_condition_.wait(lock);
00132 
00133       if (shutting_down_)
00134       {
00135         return;
00136       }
00137 
00138       local_queue.swap(log_queue_);
00139     }
00140 
00141     V_Log::iterator it = local_queue.begin();
00142     V_Log::iterator end = local_queue.end();
00143     for (; it != end; ++it)
00144     {
00145       TopicManager::instance()->publish(names::resolve("/rosout"), *(*it));
00146     }
00147   }
00148 }
00149 
00150 } // namespace ros


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Tue Mar 7 2017 03:44:47