| Home | Trees | Indices | Help |
|
|---|
|
|
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2008, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 #
33 # Revision $Id$
34
35 """Internal use: support for /rosout logging in rospy"""
36
37 import logging
38 import sys
39 import traceback
40
41 import rospy.names
42
43 from rospy.core import get_caller_id
44 from rospy.exceptions import ROSException
45 from rospy.topics import Publisher, Subscriber
46 from rospy.rostime import Time
47
48 from rospy.impl.registration import get_topic_manager
49
50 #Log message for rosout
51 from rosgraph_msgs.msg import Log
52
53 _ROSOUT = '/rosout'
54 _rosout_pub = None
55
56 _rospy_to_logging_levels = {
57 Log.DEBUG: logging.DEBUG,
58 Log.INFO: logging.INFO,
59 Log.WARN: logging.WARNING,
60 Log.ERROR: logging.ERROR,
61 Log.FATAL: logging.CRITICAL,
62 }
63
65 logger = logging.getLogger("rospy.rosout")
66 try:
67 global _rosout_pub
68 if _rosout_pub is None:
69 logger.info("initializing %s core topic"%_ROSOUT)
70 _rosout_pub = Publisher(_ROSOUT, Log, latch=True)
71 logger.info("connected to core topic %s"%_ROSOUT)
72 return True
73 except Exception as e:
74 logger.error("Unable to initialize %s: %s\n%s", _ROSOUT, e, traceback.format_exc())
75 return False
76
77 _in_rosout = False
78 ## log an error to the /rosout topic
80 global _in_rosout
81 try:
82 if _rosout_pub is not None:
83 # protect against infinite recursion
84 if not _in_rosout:
85 try:
86 _in_rosout = True
87 msg = str(msg)
88 topics = get_topic_manager().get_topics()
89 l = Log(level=level, name=str(rospy.names.get_caller_id()), msg=str(msg), topics=topics, file=fname, line=line, function=func)
90 l.header.stamp = Time.now()
91 _rosout_pub.publish(l)
92 finally:
93 _in_rosout = False
94 except Exception as e:
95 #traceback.print_exc()
96 # don't use logerr in this case as that is recursive here
97 logger = logging.getLogger("rospy.rosout")
98 logger.error("Unable to report rosout: %s\n%s", e, traceback.format_exc())
99 return False
100
101 _logging_to_rospy_levels = {
102 logging.DEBUG: Log.DEBUG,
103 logging.INFO: Log.INFO,
104 logging.WARNING: Log.WARN,
105 logging.ERROR: Log.ERROR,
106 logging.CRITICAL: Log.FATAL,
107 }
108
111 _rosout(_logging_to_rospy_levels[record.levelno], record.getMessage(),
112 record.filename, record.lineno, record.funcName)
113
114 ## Load loggers for publishing to /rosout
115 ## @param level int: Log level. Loggers >= level will be loaded.
117 logger = logging.getLogger('rosout')
118 logger.addHandler(RosOutHandler())
119 if level != None:
120 logger.setLevel(_rospy_to_logging_levels[level])
121
| Home | Trees | Indices | Help |
|
|---|
| Generated by Epydoc 3.0.1 on Fri Aug 28 12:33:29 2015 | http://epydoc.sourceforge.net |