file_log.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2009, Willow Garage, Inc.
00003  *
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
00026  */
00027 
00028 #include <cstdio>
00029 #include "ros/file_log.h"
00030 #include "ros/this_node.h"
00031 
00032 #include "log4cxx/rollingfileappender.h"
00033 #include "log4cxx/patternlayout.h"
00034 #include <ros/io.h>
00035 #include <ros/console.h>
00036 
00037 #include <boost/filesystem.hpp>
00038 
00039 #ifdef _MSC_VER
00040   #ifdef snprintf
00041     #undef snprintf
00042   #endif
00043   #define snprintf _snprintf_s
00044 #endif
00045 
00046 
00047 namespace fs = boost::filesystem;
00048 
00049 namespace ros
00050 {
00051 
00052 namespace file_log
00053 {
00054 
00055 std::string g_log_directory;
00056 log4cxx::LoggerPtr g_file_only_logger;
00057 
00058 const std::string& getLogDirectory()
00059 {
00060   return g_log_directory;
00061 }
00062 
00063 void init(const M_string& remappings)
00064 {
00065   std::string log_file_name;
00066   M_string::const_iterator it = remappings.find("__log");
00067   if (it != remappings.end())
00068   {
00069     log_file_name = it->second;
00070   }
00071 
00072   {
00073     // Log filename can be specified on the command line through __log
00074     // If it's been set, don't create our own name
00075     if (log_file_name.empty())
00076     {
00077       // Setup the logfile appender
00078       // Can't do this in rosconsole because the node name is not known
00079       pid_t pid = getpid();
00080       std::string ros_log_env;
00081       if ( get_environment_variable(ros_log_env, "ROS_LOG_DIR"))
00082       {
00083         log_file_name = ros_log_env + std::string("/");
00084       }
00085       else
00086       {
00087         if ( get_environment_variable(ros_log_env, "ROS_HOME"))
00088         {
00089           log_file_name = ros_log_env + std::string("/log/");
00090         }
00091         else
00092         {
00093           // Not cross-platform?
00094           if( get_environment_variable(ros_log_env, "HOME") )
00095           {
00096             std::string dotros = ros_log_env + std::string("/.ros/");
00097             fs::create_directory(dotros);
00098             log_file_name = dotros + "log/";
00099             fs::create_directory(log_file_name);
00100           }
00101         }
00102       }
00103 
00104       // sanitize the node name and tack it to the filename
00105       for (size_t i = 1; i < this_node::getName().length(); i++)
00106       {
00107         if (!isalnum(this_node::getName()[i]))
00108         {
00109           log_file_name += '_';
00110         }
00111         else
00112         {
00113           log_file_name += this_node::getName()[i];
00114         }
00115       }
00116 
00117       char pid_str[100];
00118       snprintf(pid_str, sizeof(pid_str), "%d", pid);
00119       log_file_name += std::string("_") + std::string(pid_str) + std::string(".log");
00120     }
00121 
00122     log_file_name = fs::system_complete(log_file_name).string();
00123     g_log_directory = fs::path(log_file_name).parent_path().string();
00124   }
00125 }
00126 
00127 } // namespace file_log
00128 
00129 } // 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