init.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, 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/init.h"
36 #include "ros/names.h"
37 #include "ros/xmlrpc_manager.h"
38 #include "ros/poll_manager.h"
39 #include "ros/connection_manager.h"
40 #include "ros/topic_manager.h"
41 #include "ros/service_manager.h"
42 #include "ros/this_node.h"
43 #include "ros/network.h"
44 #include "ros/file_log.h"
45 #include "ros/callback_queue.h"
46 #include "ros/param.h"
47 #include "ros/rosout_appender.h"
48 #include "ros/subscribe_options.h"
51 #include "xmlrpcpp/XmlRpcSocket.h"
52 
53 #include "roscpp/GetLoggers.h"
54 #include "roscpp/SetLoggerLevel.h"
55 #include "roscpp/Empty.h"
56 
57 #include <ros/console.h>
58 #include <ros/time.h>
59 #include <rosgraph_msgs/Clock.h>
60 
61 #include <algorithm>
62 
63 #include <signal.h>
64 
65 #include <cstdlib>
66 
67 namespace ros
68 {
69 
70 namespace master
71 {
72 void init(const M_string& remappings);
73 }
74 
75 namespace this_node
76 {
77 void init(const std::string& names, const M_string& remappings, uint32_t options);
78 }
79 
80 namespace network
81 {
82 void init(const M_string& remappings);
83 }
84 
85 namespace param
86 {
87 void init(const M_string& remappings);
88 }
89 
90 namespace file_log
91 {
92 void init(const M_string& remappings);
93 }
94 
98 
99 static bool g_initialized = false;
100 static bool g_started = false;
101 static bool g_atexit_registered = false;
102 static bool g_shutdown_registered = false;
103 static boost::mutex g_start_mutex;
104 static bool g_ok = false;
105 static uint32_t g_init_options = 0;
106 static bool g_shutdown_requested = false;
107 static volatile bool g_shutting_down = false;
108 static boost::recursive_mutex g_shutting_down_mutex;
109 static boost::thread g_internal_queue_thread;
110 
112 {
113  return g_initialized;
114 }
115 
117 {
118  return g_shutting_down;
119 }
120 
122 {
124  {
125  // Since this gets run from within a mutex inside PollManager, we need to prevent ourselves from deadlocking with
126  // another thread that's already in the middle of shutdown()
127  boost::recursive_mutex::scoped_try_lock lock(g_shutting_down_mutex, boost::defer_lock);
128  while (!lock.try_lock() && !g_shutting_down)
129  {
130  ros::WallDuration(0.001).sleep();
131  }
132 
133  if (!g_shutting_down)
134  {
135  shutdown();
136  }
137 
138  g_shutdown_requested = false;
139  }
140 }
141 
143 {
144  g_shutdown_requested = true;
145 }
146 
148 {
149  if (ok() && !isShuttingDown())
150  {
151  ROSCPP_LOG_DEBUG("shutting down due to exit() or end of main() without cleanup of all NodeHandles");
152  g_started = false; // don't shutdown singletons, because they are already destroyed
153  shutdown();
154  }
155 }
156 
158 {
159  int num_params = 0;
160  if (params.getType() == XmlRpc::XmlRpcValue::TypeArray)
161  num_params = params.size();
162  if (num_params > 1)
163  {
164  std::string reason = params[1];
165  ROS_WARN("Shutdown request received.");
166  ROS_WARN("Reason given for shutdown: [%s]", reason.c_str());
167  requestShutdown();
168  }
169 
170  result = xmlrpc::responseInt(1, "", 0);
171 }
172 
173 bool getLoggers(roscpp::GetLoggers::Request&, roscpp::GetLoggers::Response& resp)
174 {
175  std::map<std::string, ros::console::levels::Level> loggers;
176  bool success = ::ros::console::get_loggers(loggers);
177  if (success)
178  {
179  for (std::map<std::string, ros::console::levels::Level>::const_iterator it = loggers.begin(); it != loggers.end(); it++)
180  {
181  roscpp::Logger logger;
182  logger.name = it->first;
183  ros::console::levels::Level level = it->second;
184  if (level == ros::console::levels::Debug)
185  {
186  logger.level = "debug";
187  }
188  else if (level == ros::console::levels::Info)
189  {
190  logger.level = "info";
191  }
192  else if (level == ros::console::levels::Warn)
193  {
194  logger.level = "warn";
195  }
196  else if (level == ros::console::levels::Error)
197  {
198  logger.level = "error";
199  }
200  else if (level == ros::console::levels::Fatal)
201  {
202  logger.level = "fatal";
203  }
204  resp.loggers.push_back(logger);
205  }
206  }
207  return success;
208 }
209 
210 bool setLoggerLevel(roscpp::SetLoggerLevel::Request& req, roscpp::SetLoggerLevel::Response&)
211 {
212  std::transform(req.level.begin(), req.level.end(), req.level.begin(), (int(*)(int))std::toupper);
213 
215  if (req.level == "DEBUG")
216  {
218  }
219  else if (req.level == "INFO")
220  {
222  }
223  else if (req.level == "WARN")
224  {
226  }
227  else if (req.level == "ERROR")
228  {
230  }
231  else if (req.level == "FATAL")
232  {
234  }
235  else
236  {
237  return false;
238  }
239 
240  bool success = ::ros::console::set_logger_level(req.logger, level);
241  if (success)
242  {
244  }
245 
246  return success;
247 }
248 
249 bool closeAllConnections(roscpp::Empty::Request&, roscpp::Empty::Response&)
250 {
251  ROSCPP_LOG_DEBUG("close_all_connections service called, closing connections");
253  return true;
254 }
255 
256 void clockCallback(const rosgraph_msgs::Clock::ConstPtr& msg)
257 {
258  Time::setNow(msg->clock);
259 }
260 
262 {
264  {
266  }
267 
269 }
270 
271 void basicSigintHandler(int sig)
272 {
273  (void)sig;
275 }
276 
278 {
279  disableAllSignalsInThisThread();
280 
282 
283  while (!g_shutting_down)
284  {
285  queue->callAvailable(WallDuration(0.1));
286  }
287 }
288 
289 bool isStarted()
290 {
291  return g_started;
292 }
293 
294 void start()
295 {
296  boost::mutex::scoped_lock lock(g_start_mutex);
297  if (g_started)
298  {
299  return;
300  }
301 
302  g_shutdown_requested = false;
303  g_shutting_down = false;
304  g_started = true;
305  g_ok = true;
306 
307  bool enable_debug = false;
308  std::string enable_debug_env;
309  if ( get_environment_variable(enable_debug_env,"ROSCPP_ENABLE_DEBUG") )
310  {
311  try
312  {
313  enable_debug = boost::lexical_cast<bool>(enable_debug_env.c_str());
314  }
315  catch (boost::bad_lexical_cast&)
316  {
317  }
318  }
319 
321 
322  PollManager::instance()->addPollThreadListener(checkForShutdown);
323  XMLRPCManager::instance()->bind("shutdown", shutdownCallback);
324 
326 
327  TopicManager::instance()->start();
328  ServiceManager::instance()->start();
329  ConnectionManager::instance()->start();
330  PollManager::instance()->start();
331  XMLRPCManager::instance()->start();
332 
334  {
335  signal(SIGINT, basicSigintHandler);
336  }
337 
338  ros::Time::init();
339 
340  bool no_rosout = false;
341  std::string no_rosout_env;
342  if (get_environment_variable(no_rosout_env,"ROSCPP_NO_ROSOUT"))
343  {
344  try
345  {
346  no_rosout = boost::lexical_cast<bool>(no_rosout_env.c_str());
347  }
348  catch (boost::bad_lexical_cast&)
349  {
350  }
351  }
352 
353  if (!(no_rosout || (g_init_options & init_options::NoRosout)))
354  {
357  }
358 
359  if (g_shutting_down) goto end;
360 
361  {
363  ops.init<roscpp::GetLoggers>(names::resolve("~get_loggers"), getLoggers);
365  ServiceManager::instance()->advertiseService(ops);
366  }
367 
368  if (g_shutting_down) goto end;
369 
370  {
372  ops.init<roscpp::SetLoggerLevel>(names::resolve("~set_logger_level"), setLoggerLevel);
374  ServiceManager::instance()->advertiseService(ops);
375  }
376 
377  if (g_shutting_down) goto end;
378 
379  if (enable_debug)
380  {
382  ops.init<roscpp::Empty>(names::resolve("~debug/close_all_connections"), closeAllConnections);
384  ServiceManager::instance()->advertiseService(ops);
385  }
386 
387  if (g_shutting_down) goto end;
388 
389  {
390  bool use_sim_time = false;
391  param::param("/use_sim_time", use_sim_time, use_sim_time);
392 
393  if (use_sim_time)
394  {
396  }
397 
398  if (g_shutting_down) goto end;
399 
400  if (use_sim_time)
401  {
403  ops.init<rosgraph_msgs::Clock>(names::resolve("/clock"), 1, clockCallback);
405  TopicManager::instance()->subscribe(ops);
406  }
407  }
408 
409  if (g_shutting_down) goto end;
410 
412 
413  // Ensure that shutdown() is always called when the program exits,
414  // but before singletons get destroyed, so that the internal queue thread is joined first
415  // and cannot access destroyed singletons.
417  {
418  g_shutdown_registered = true;
419  atexit(shutdown);
420  }
421 
423 
424  ROSCPP_LOG_DEBUG("Started node [%s], pid [%d], bound on [%s], xmlrpc port [%d], tcpros port [%d], using [%s] time",
425  this_node::getName().c_str(), getpid(), network::getHost().c_str(),
426  XMLRPCManager::instance()->getServerPort(), ConnectionManager::instance()->getTCPPort(),
427  Time::useSystemTime() ? "real" : "sim");
428 
429  // Label used to abort if we've started shutting down in the middle of start(), which can happen in
430  // threaded code or if Ctrl-C is pressed while we're initializing
431 end:
432  // If we received a shutdown request while initializing, wait until we've shutdown to continue
433  if (g_shutting_down)
434  {
435  boost::recursive_mutex::scoped_lock lock(g_shutting_down_mutex);
436  }
437 }
438 
440  char* env_ipv6 = NULL;
441 #ifdef _MSC_VER
442  _dupenv_s(&env_ipv6, NULL, "ROS_IPV6");
443 #else
444  env_ipv6 = getenv("ROS_IPV6");
445 #endif
446 
447  bool use_ipv6 = (env_ipv6 && strcmp(env_ipv6,"on") == 0);
448  TransportTCP::s_use_ipv6_ = use_ipv6;
450 
451 #ifdef _MSC_VER
452  if (env_ipv6)
453  {
454  free(env_ipv6);
455  }
456 #endif
457 }
458 
459 void init(const M_string& remappings, const std::string& name, uint32_t options)
460 {
461  if (!g_atexit_registered)
462  {
463  g_atexit_registered = true;
464  atexit(atexitCallback);
465  }
466 
467  if (!g_global_queue)
468  {
469  g_global_queue.reset(new CallbackQueue);
470  }
471 
472  if (!g_initialized)
473  {
474  g_init_options = options;
475  g_ok = true;
476 
478  // Disable SIGPIPE
479 #ifndef WIN32
480  signal(SIGPIPE, SIG_IGN);
481 #else
482  WSADATA wsaData;
483  WSAStartup(MAKEWORD(2, 0), &wsaData);
484 #endif
486  network::init(remappings);
487  master::init(remappings);
488  // names:: namespace is initialized by this_node
489  this_node::init(name, remappings, options);
490  file_log::init(remappings);
491  param::init(remappings);
492 
493  g_initialized = true;
494  }
495 }
496 
497 void init(int& argc, char** argv, const std::string& name, uint32_t options)
498 {
499  M_string remappings;
500 
501  int full_argc = argc;
502  // now, move the remapping argv's to the end, and decrement argc as needed
503  for (int i = 0; i < argc; )
504  {
505  std::string arg = argv[i];
506  size_t pos = arg.find(":=");
507  if (pos != std::string::npos)
508  {
509  std::string local_name = arg.substr(0, pos);
510  std::string external_name = arg.substr(pos + 2);
511 
512  ROSCPP_LOG_DEBUG("remap: %s => %s", local_name.c_str(), external_name.c_str());
513  remappings[local_name] = external_name;
514 
515  // shuffle everybody down and stuff this guy at the end of argv
516  char *tmp = argv[i];
517  for (int j = i; j < full_argc - 1; j++)
518  argv[j] = argv[j+1];
519  argv[argc-1] = tmp;
520  argc--;
521  }
522  else
523  {
524  i++; // move on, since we didn't shuffle anybody here to replace it
525  }
526  }
527 
528  init(remappings, name, options);
529 }
530 
531 void init(const VP_string& remappings, const std::string& name, uint32_t options)
532 {
533  M_string remappings_map;
534  VP_string::const_iterator it = remappings.begin();
535  VP_string::const_iterator end = remappings.end();
536  for (; it != end; ++it)
537  {
538  remappings_map[it->first] = it->second;
539  }
540 
541  init(remappings_map, name, options);
542 }
543 
544 std::string getROSArg(int argc, const char* const* argv, const std::string& arg)
545 {
546  for (int i = 0; i < argc; ++i)
547  {
548  std::string str_arg = argv[i];
549  size_t pos = str_arg.find(":=");
550  if (str_arg.substr(0,pos) == arg)
551  {
552  return str_arg.substr(pos+2);
553  }
554  }
555  return "";
556 }
557 
558 void removeROSArgs(int argc, const char* const* argv, V_string& args_out)
559 {
560  for (int i = 0; i < argc; ++i)
561  {
562  std::string arg = argv[i];
563  size_t pos = arg.find(":=");
564  if (pos == std::string::npos)
565  {
566  args_out.push_back(arg);
567  }
568  }
569 }
570 
571 void spin()
572 {
574  spin(s);
575 }
576 
577 void spin(Spinner& s)
578 {
579  s.spin();
580 }
581 
582 void spinOnce()
583 {
584  g_global_queue->callAvailable(ros::WallDuration());
585 }
586 
588 {
589  while (ok())
590  {
591  WallDuration(0.05).sleep();
592  }
593 }
594 
596 {
597  return g_global_queue.get();
598 }
599 
600 bool ok()
601 {
602  return g_ok;
603 }
604 
605 void shutdown()
606 {
607  boost::recursive_mutex::scoped_lock lock(g_shutting_down_mutex);
608  if (g_shutting_down)
609  return;
610  else
611  g_shutting_down = true;
612 
614 
615  g_global_queue->disable();
616  g_global_queue->clear();
617 
618  if (g_internal_queue_thread.get_id() != boost::this_thread::get_id())
619  {
621  }
622  //ros::console::deregister_appender(g_rosout_appender);
623  delete g_rosout_appender;
624  g_rosout_appender = 0;
625 
626  if (g_started)
627  {
628  TopicManager::instance()->shutdown();
629  ServiceManager::instance()->shutdown();
630  PollManager::instance()->shutdown();
631  ConnectionManager::instance()->shutdown();
632  XMLRPCManager::instance()->shutdown();
633  }
634 
635  g_started = false;
636  g_ok = false;
637  Time::shutdown();
638 }
639 
640 const std::string& getDefaultMasterURI() {
641  static const std::string uri = "http://localhost:11311";
642  return uri;
643 }
644 
645 }
XmlRpc::XmlRpcValue::size
int size() const
connection_manager.h
ros::init_options::NoRosout
@ NoRosout
Don't broadcast rosconsole output to the /rosout topic.
Definition: init.h:63
ros::network::init
void init(const M_string &remappings)
Definition: network.cpp:187
this_node.h
ros::WallDuration::sleep
bool sleep() const
ros::g_init_options
static uint32_t g_init_options
Definition: init.cpp:105
ros::g_shutting_down
static volatile bool g_shutting_down
Definition: init.cpp:107
ros::check_ipv6_environment
void check_ipv6_environment()
Definition: init.cpp:439
ros::console::levels::Error
Error
ros::init
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROS initialization function.
Definition: init.cpp:497
ros::AdvertiseServiceOptions::init
void init(const std::string &_service, const boost::function< bool(MReq &, MRes &)> &_callback)
Templated convenience method for filling out md5sum/etc. based on the service request/response types.
Definition: advertise_service_options.h:56
ros::g_shutdown_registered
static bool g_shutdown_registered
Definition: init.cpp:102
ros::atexitCallback
void atexitCallback()
Definition: init.cpp:147
boost::shared_ptr
ros::g_internal_queue_thread
static boost::thread g_internal_queue_thread
Definition: init.cpp:109
XmlRpc::XmlRpcSocket::s_use_ipv6_
static bool s_use_ipv6_
ros::g_rosout_appender
ROSOutAppender * g_rosout_appender
Definition: init.cpp:96
ros::param::param
bool param(const std::string &param_name, T &param_val, const T &default_val)
Assign value from parameter server, with default.
Definition: param.h:619
ros::master::init
void init(const M_string &remappings)
Definition: master.cpp:50
ros::xmlrpc::responseInt
ROSCPP_DECL XmlRpc::XmlRpcValue responseInt(int code, const std::string &msg, int response)
Definition: xmlrpc_manager.cpp:52
s
XmlRpcServer s
ros
ros::Spinner
Abstract interface for classes which spin on a callback queue.
Definition: spinner.h:44
time.h
ros::param::init
void init(const M_string &remappings)
Definition: param.cpp:826
service_manager.h
ros::basicSigintHandler
void basicSigintHandler(int sig)
Definition: init.cpp:271
ros::spinOnce
ROSCPP_DECL void spinOnce()
Process a single round of callbacks.
Definition: init.cpp:582
ros::TransportTCP::s_use_keepalive_
static bool s_use_keepalive_
Definition: transport_tcp.h:59
ros::SubscribeOptions::callback_queue
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition: subscribe_options.h:123
ros::ROSOutAppender
Definition: rosout_appender.h:59
ros::shutdown
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
Definition: init.cpp:605
ros::g_started
static bool g_started
Definition: init.cpp:100
ros::Time::setNow
static void setNow(const Time &new_now)
ros::Time::shutdown
static void shutdown()
ros::Connection::TransportDisconnect
@ TransportDisconnect
Definition: connection.h:75
ros::ServiceManager::instance
static const ServiceManagerPtr & instance()
Definition: service_manager.cpp:55
ros::VP_string
std::vector< std::pair< std::string, std::string > > VP_string
ros::g_global_queue
CallbackQueuePtr g_global_queue
Definition: init.cpp:95
ros::requestShutdown
ROSCPP_DECL void requestShutdown()
Request that the node shut itself down from within a ROS thread.
Definition: init.cpp:142
ros::ok
ROSCPP_DECL bool ok()
Check whether it's time to exit.
Definition: init.cpp:600
ros::names::resolve
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
ROSCONSOLE_AUTOINIT
#define ROSCONSOLE_AUTOINIT
ros::network::getHost
const ROSCPP_DECL std::string & getHost()
Definition: network.cpp:51
topic_manager.h
ros::SubscribeOptions::init
void init(const std::string &_topic, uint32_t _queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &_callback, const boost::function< boost::shared_ptr< M >(void)> &factory_fn=DefaultMessageCreator< M >())
Templated initialization, templated on message type. Only supports "const boost::shared_ptr<M const>&...
Definition: subscribe_options.h:103
ros::console::register_appender
ROSCONSOLE_DECL void register_appender(LogAppender *appender)
console.h
ros::this_node::init
void init(const std::string &names, const M_string &remappings, uint32_t options)
Definition: this_node.cpp:94
ros::console::levels::Debug
Debug
ros::console::shutdown
ROSCONSOLE_DECL void shutdown()
ros::Time::useSystemTime
static bool useSystemTime()
init.h
ros::AdvertiseServiceOptions::callback_queue
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition: advertise_service_options.h:126
ros::g_shutting_down_mutex
static boost::recursive_mutex g_shutting_down_mutex
Definition: init.cpp:108
ros::g_ok
static bool g_ok
Definition: init.cpp:104
subscribe_options.h
param.h
ros::SingleThreadedSpinner
Spinner which runs in a single thread.
Definition: spinner.h:58
ros::isInitialized
ROSCPP_DECL bool isInitialized()
Returns whether or not ros::init() has been called.
Definition: init.cpp:111
ros::closeAllConnections
bool closeAllConnections(roscpp::Empty::Request &, roscpp::Empty::Response &)
Definition: init.cpp:249
transport_tcp.h
ROS_WARN
#define ROS_WARN(...)
ros::setLoggerLevel
bool setLoggerLevel(roscpp::SetLoggerLevel::Request &req, roscpp::SetLoggerLevel::Response &)
Definition: init.cpp:210
ros::getLoggers
bool getLoggers(roscpp::GetLoggers::Request &, roscpp::GetLoggers::Response &resp)
Definition: init.cpp:173
ros::XMLRPCManager::instance
static const XMLRPCManagerPtr & instance()
Definition: xmlrpc_manager.cpp:98
ros::AdvertiseServiceOptions
Encapsulates all options available for creating a ServiceServer.
Definition: advertise_service_options.h:43
ros::g_internal_callback_queue
static CallbackQueuePtr g_internal_callback_queue
Definition: init.cpp:97
ros::PollManager::instance
static const PollManagerPtr & instance()
Definition: poll_manager.cpp:36
xmlrpc_manager.h
ros::shutdownCallback
void shutdownCallback(XmlRpc::XmlRpcValue &params, XmlRpc::XmlRpcValue &result)
Definition: init.cpp:157
ros::isStarted
ROSCPP_DECL bool isStarted()
Returns whether or not the node has been started through ros::start()
Definition: init.cpp:289
ros::g_start_mutex
static boost::mutex g_start_mutex
Definition: init.cpp:103
ros::console::levels::Level
Level
ros::console::levels::Info
Info
XmlRpc::XmlRpcValue::getType
const Type & getType() const
XmlRpcSocket.h
XmlRpc::XmlRpcValue::TypeArray
TypeArray
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
Returns the name of the current node.
Definition: this_node.cpp:74
ros::start
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
Definition: init.cpp:294
ros::Time::init
static void init()
ros::g_shutdown_requested
static bool g_shutdown_requested
Definition: init.cpp:106
ros::SubscribeOptions
Encapsulates all options available for creating a Subscriber.
Definition: subscribe_options.h:43
ros::console::levels::Fatal
Fatal
ros::console::notifyLoggerLevelsChanged
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
ros::Time
ros::CallbackQueue
This is the default implementation of the ros::CallbackQueueInterface.
Definition: callback_queue.h:57
ros::get_environment_variable
bool get_environment_variable(std::string &str, const char *environment_variable)
ros::clockCallback
void clockCallback(const rosgraph_msgs::Clock::ConstPtr &msg)
Definition: init.cpp:256
ros::CallbackQueue::enable
void enable()
Enable the queue (queue is enabled by default)
Definition: callback_queue.cpp:53
poll_manager.h
ros::TopicManager::instance
static const TopicManagerPtr & instance()
Definition: topic_manager.cpp:56
ros::internalCallbackQueueThreadFunc
void internalCallbackQueueThreadFunc()
Definition: init.cpp:277
ros::g_atexit_registered
static bool g_atexit_registered
Definition: init.cpp:101
ros::waitForShutdown
ROSCPP_DECL void waitForShutdown()
Wait for this node to be shutdown, whether through Ctrl-C, ros::shutdown(), or similar.
Definition: init.cpp:587
internal_timer_manager.h
network.h
ros::ConnectionManager::instance
static const ConnectionManagerPtr & instance()
Definition: connection_manager.cpp:43
ros::isShuttingDown
ROSCPP_DECL bool isShuttingDown()
Returns whether or not ros::shutdown() has been (or is being) called.
Definition: init.cpp:116
ros::getROSArg
ROSCPP_DECL std::string getROSArg(int argc, const char *const *argv, const std::string &arg)
searches the command line arguments for the given arg parameter. In case this argument is not found a...
Definition: init.cpp:544
ros::getInternalCallbackQueue
CallbackQueuePtr getInternalCallbackQueue()
Definition: init.cpp:261
ros::TransportTCP::s_use_ipv6_
static bool s_use_ipv6_
Definition: transport_tcp.h:60
ros::file_log::init
void init(const M_string &remappings)
Definition: file_log.cpp:52
ros::console::levels::Warn
Warn
ros::spin
ROSCPP_DECL void spin()
Enter simple event loop.
Definition: init.cpp:571
rosout_appender.h
ros::V_string
std::vector< std::string > V_string
callback_queue.h
ros::getDefaultMasterURI
const ROSCPP_DECL std::string & getDefaultMasterURI()
returns the default master uri that is used if no other is specified, e.g. by defining ROS_MASTER_URI...
Definition: init.cpp:640
ros::removeROSArgs
ROSCPP_DECL void removeROSArgs(int argc, const char *const *argv, V_string &args_out)
returns a vector of program arguments that do not include any ROS remapping arguments....
Definition: init.cpp:558
names.h
ros::WallDuration
ros::initInternalTimerManager
ROSCPP_DECL void initInternalTimerManager()
Definition: internal_timer_manager.cpp:41
ros::init_options::NoSigintHandler
@ NoSigintHandler
Definition: init.h:56
ROSCPP_LOG_DEBUG
#define ROSCPP_LOG_DEBUG(...)
Definition: file_log.h:35
XmlRpc::XmlRpcValue
ros::checkForShutdown
void checkForShutdown()
Definition: init.cpp:121
ros::g_initialized
static bool g_initialized
Definition: init.cpp:99
file_log.h
ros::getGlobalCallbackQueue
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
Returns a pointer to the global default callback queue.
Definition: init.cpp:595
M_string
std::map< std::string, std::string > M_string


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:44