ompl_console.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, 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 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 /* Author: Ioan Sucan */
00036 
00037 #include <ros/console.h>
00038 #include <ompl/util/Console.h>
00039 
00040 namespace ompl_inteface
00041 {
00042 class OutputHandlerROS : public ompl::msg::OutputHandler
00043 {
00044 public:
00045   OutputHandlerROS() : OutputHandler()
00046   {
00047   }
00048 
00049   virtual void log(const std::string& text, ompl::msg::LogLevel level, const char* filename, int line)
00050   {
00051     switch (level)
00052     {
00053       case ompl::msg::LOG_INFO:
00054       {
00055         ROSCONSOLE_DEFINE_LOCATION(true, ::ros::console::levels::Info, std::string(ROSCONSOLE_ROOT_LOGGER_NAME) + ".omp"
00056                                                                                                                   "l");
00057         if (ROS_UNLIKELY(__rosconsole_define_location__enabled))
00058         {
00059           ::ros::console::print(NULL, __rosconsole_define_location__loc.logger_,
00060                                 __rosconsole_define_location__loc.level_, filename, line, "", "%s", text.c_str());
00061         }
00062       }
00063       break;
00064       case ompl::msg::LOG_WARN:
00065       {
00066         ROSCONSOLE_DEFINE_LOCATION(true, ::ros::console::levels::Warn, std::string(ROSCONSOLE_ROOT_LOGGER_NAME) + ".omp"
00067                                                                                                                   "l");
00068         if (ROS_UNLIKELY(__rosconsole_define_location__enabled))
00069         {
00070           ::ros::console::print(NULL, __rosconsole_define_location__loc.logger_,
00071                                 __rosconsole_define_location__loc.level_, filename, line, "", "%s", text.c_str());
00072         }
00073       }
00074       break;
00075       case ompl::msg::LOG_ERROR:
00076       {
00077         ROSCONSOLE_DEFINE_LOCATION(true, ::ros::console::levels::Error,
00078                                    std::string(ROSCONSOLE_ROOT_LOGGER_NAME) + ".ompl");
00079         if (ROS_UNLIKELY(__rosconsole_define_location__enabled))
00080         {
00081           ::ros::console::print(NULL, __rosconsole_define_location__loc.logger_,
00082                                 __rosconsole_define_location__loc.level_, filename, line, "", "%s", text.c_str());
00083         }
00084       }
00085       break;
00086       default:
00087         // debug
00088         {
00089           ROSCONSOLE_DEFINE_LOCATION(true, ::ros::console::levels::Debug,
00090                                      std::string(ROSCONSOLE_ROOT_LOGGER_NAME) + ".ompl");
00091           if (ROS_UNLIKELY(__rosconsole_define_location__enabled))
00092           {
00093             ::ros::console::print(NULL, __rosconsole_define_location__loc.logger_,
00094                                   __rosconsole_define_location__loc.level_, filename, line, "", "%s", text.c_str());
00095           }
00096         }
00097         break;
00098     }
00099   }
00100 };
00101 
00102 struct RegisterOH
00103 {
00104   RegisterOH()
00105   {
00106     static OutputHandlerROS oh_ros;
00107     ompl::msg::useOutputHandler(&oh_ros);
00108     ompl::msg::setLogLevel(ompl::msg::LOG_DEBUG);
00109   }
00110 };
00111 
00112 static RegisterOH proxy;
00113 }


ompl
Author(s): Ioan Sucan
autogenerated on Wed Jun 19 2019 19:24:27