rosout_appender.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include "ros/rosout_appender.h"
36 #include "ros/this_node.h"
37 #include "ros/node_handle.h"
38 #include "ros/topic_manager.h"
39 #include "ros/advertise_options.h"
40 #include "ros/names.h"
41 #include "ros/param.h"
42 
43 #include <rosgraph_msgs/Log.h>
44 
45 namespace ros
46 {
47 
49 : shutting_down_(false)
50 , disable_topics_(false)
51 , publish_thread_(boost::bind(&ROSOutAppender::logThread, this))
52 {
53  AdvertiseOptions ops;
54  ops.init<rosgraph_msgs::Log>(names::resolve("/rosout"), 0);
55  ops.latch = true;
56  SubscriberCallbacksPtr cbs(boost::make_shared<SubscriberCallbacks>());
57  TopicManager::instance()->advertise(ops, cbs);
58 }
59 
61 {
62  shutting_down_ = true;
63 
64  {
65  boost::mutex::scoped_lock lock(queue_mutex_);
66  queue_condition_.notify_all();
67  }
68 
69  publish_thread_.join();
70 }
71 
72 const std::string& ROSOutAppender::getLastError() const
73 {
74  return last_error_;
75 }
76 
77 void ROSOutAppender::log(::ros::console::Level level, const char* str, const char* file, const char* function, int line)
78 {
79  rosgraph_msgs::LogPtr msg(boost::make_shared<rosgraph_msgs::Log>());
80 
81  msg->header.stamp = ros::Time::now();
82  if (level == ros::console::levels::Debug)
83  {
84  msg->level = rosgraph_msgs::Log::DEBUG;
85  }
86  else if (level == ros::console::levels::Info)
87  {
88  msg->level = rosgraph_msgs::Log::INFO;
89  }
90  else if (level == ros::console::levels::Warn)
91  {
92  msg->level = rosgraph_msgs::Log::WARN;
93  }
94  else if (level == ros::console::levels::Error)
95  {
96  msg->level = rosgraph_msgs::Log::ERROR;
97  }
98  else if (level == ros::console::levels::Fatal)
99  {
100  msg->level = rosgraph_msgs::Log::FATAL;
101  }
102  msg->name = this_node::getName();
103  msg->msg = str;
104  msg->file = file;
105  msg->function = function;
106  msg->line = line;
107 
108  // check parameter server/cache for omit_topics flag
109  // the same parameter is checked in rosout.py for the same purpose
110  ros::param::getCached("/rosout_disable_topics_generation", disable_topics_);
111 
112  if (!disable_topics_){
113  this_node::getAdvertisedTopics(msg->topics);
114  }
115 
116  if (level == ::ros::console::levels::Fatal || level == ::ros::console::levels::Error)
117  {
118  last_error_ = str;
119  }
120 
121  boost::mutex::scoped_lock lock(queue_mutex_);
122  log_queue_.push_back(msg);
123  queue_condition_.notify_all();
124 }
125 
127 {
128  while (!shutting_down_)
129  {
130  V_Log local_queue;
131 
132  {
133  boost::mutex::scoped_lock lock(queue_mutex_);
134 
135  if (shutting_down_)
136  {
137  return;
138  }
139 
140  if (log_queue_.empty())
141  {
142  queue_condition_.wait(lock);
143  }
144 
145  if (shutting_down_)
146  {
147  return;
148  }
149 
150  local_queue.swap(log_queue_);
151  }
152 
153  V_Log::iterator it = local_queue.begin();
154  V_Log::iterator end = local_queue.end();
155  for (; it != end; ++it)
156  {
157  TopicManager::instance()->publish(names::resolve("/rosout"), *(*it));
158  }
159  }
160 }
161 
162 } // namespace ros
std::vector< rosgraph_msgs::LogPtr > V_Log
virtual void log(::ros::console::Level level, const char *str, const char *file, const char *function, int line)
std::string last_error_
void init(const std::string &_topic, uint32_t _queue_size, const SubscriberStatusCallback &_connect_cb=SubscriberStatusCallback(), const SubscriberStatusCallback &_disconnect_cb=SubscriberStatusCallback())
templated helper function for automatically filling out md5sum, datatype and message definition ...
boost::thread publish_thread_
bool latch
Whether or not this publication should "latch". A latching publication will automatically send out th...
ROSCPP_DECL const std::string & getName()
Returns the name of the current node.
Definition: this_node.cpp:74
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
Resolve a graph resource name into a fully qualified graph resource name.
Definition: names.cpp:136
Encapsulates all options available for creating a Publisher.
boost::mutex queue_mutex_
const std::string & getLastError() const
ROSCPP_DECL bool getCached(const std::string &key, std::string &s)
Get a string value from the parameter server, with local caching.
Definition: param.cpp:439
ROSCPP_DECL void getAdvertisedTopics(V_string &topics)
Get the list of topics advertised by this node.
Definition: this_node.cpp:84
static Time now()
ros::internal::condition_variable_monotonic queue_condition_
static const TopicManagerPtr & instance()


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:33:27