00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "ros/init.h"
00036 #include "ros/names.h"
00037 #include "ros/xmlrpc_manager.h"
00038 #include "ros/poll_manager.h"
00039 #include "ros/connection_manager.h"
00040 #include "ros/topic_manager.h"
00041 #include "ros/service_manager.h"
00042 #include "ros/this_node.h"
00043 #include "ros/network.h"
00044 #include "ros/file_log.h"
00045 #include "ros/callback_queue.h"
00046 #include "ros/param.h"
00047 #include "ros/rosout_appender.h"
00048 #include "ros/subscribe_options.h"
00049 #include "ros/transport/transport_tcp.h"
00050 #include "ros/internal_timer_manager.h"
00051
00052 #include "roscpp/GetLoggers.h"
00053 #include "roscpp/SetLoggerLevel.h"
00054 #include "roscpp/Empty.h"
00055
00056 #include <ros/console.h>
00057 #include <ros/time.h>
00058 #include <rosgraph_msgs/Clock.h>
00059
00060 #include <algorithm>
00061
00062 #include <signal.h>
00063
00064 #include <cstdlib>
00065
00066 namespace ros
00067 {
00068
00069 namespace master
00070 {
00071 void init(const M_string& remappings);
00072 }
00073
00074 namespace this_node
00075 {
00076 void init(const std::string& names, const M_string& remappings, uint32_t options);
00077 }
00078
00079 namespace network
00080 {
00081 void init(const M_string& remappings);
00082 }
00083
00084 namespace param
00085 {
00086 void init(const M_string& remappings);
00087 }
00088
00089 namespace file_log
00090 {
00091 void init(const M_string& remappings);
00092 }
00093
00094 CallbackQueuePtr g_global_queue;
00095 ROSOutAppenderPtr g_rosout_appender;
00096 static CallbackQueuePtr g_internal_callback_queue;
00097
00098 static bool g_initialized = false;
00099 static bool g_started = false;
00100 static bool g_atexit_registered = false;
00101 static boost::mutex g_start_mutex;
00102 static bool g_ok = false;
00103 static uint32_t g_init_options = 0;
00104 static bool g_shutdown_requested = false;
00105 static volatile bool g_shutting_down = false;
00106 static boost::recursive_mutex g_shutting_down_mutex;
00107 static boost::thread g_internal_queue_thread;
00108
00109 bool isInitialized()
00110 {
00111 return g_initialized;
00112 }
00113
00114 bool isShuttingDown()
00115 {
00116 return g_shutting_down;
00117 }
00118
00119 void checkForShutdown()
00120 {
00121 if (g_shutdown_requested)
00122 {
00123
00124
00125 boost::recursive_mutex::scoped_try_lock lock(g_shutting_down_mutex, boost::defer_lock);
00126 while (!lock.try_lock() && !g_shutting_down)
00127 {
00128 ros::WallDuration(0.001).sleep();
00129 }
00130
00131 if (!g_shutting_down)
00132 {
00133 shutdown();
00134 }
00135
00136 g_shutdown_requested = false;
00137 }
00138 }
00139
00140 void requestShutdown()
00141 {
00142 g_shutdown_requested = true;
00143 }
00144
00145 void atexitCallback()
00146 {
00147 if (ok() && !isShuttingDown())
00148 {
00149 ROSCPP_LOG_DEBUG("shutting down due to exit() or end of main() without cleanup of all NodeHandles");
00150 shutdown();
00151 }
00152 }
00153
00154 void shutdownCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
00155 {
00156 int num_params = 0;
00157 if (params.getType() == XmlRpc::XmlRpcValue::TypeArray)
00158 num_params = params.size();
00159 if (num_params > 1)
00160 {
00161 std::string reason = params[1];
00162 ROS_WARN("Shutdown request received.");
00163 ROS_WARN("Reason given for shutdown: [%s]", reason.c_str());
00164 requestShutdown();
00165 }
00166
00167 result = xmlrpc::responseInt(1, "", 0);
00168 }
00169
00170 bool getLoggers(roscpp::GetLoggers::Request&, roscpp::GetLoggers::Response& resp)
00171 {
00172 log4cxx::spi::LoggerRepositoryPtr repo = log4cxx::Logger::getLogger(ROSCONSOLE_ROOT_LOGGER_NAME)->getLoggerRepository();
00173
00174 log4cxx::LoggerList loggers = repo->getCurrentLoggers();
00175 log4cxx::LoggerList::iterator it = loggers.begin();
00176 log4cxx::LoggerList::iterator end = loggers.end();
00177 for (; it != end; ++it)
00178 {
00179 roscpp::Logger logger;
00180 logger.name = (*it)->getName();
00181 const log4cxx::LevelPtr& level = (*it)->getEffectiveLevel();
00182 if (level)
00183 {
00184 logger.level = level->toString();
00185 }
00186 resp.loggers.push_back(logger);
00187 }
00188
00189 return true;
00190 }
00191
00192 bool setLoggerLevel(roscpp::SetLoggerLevel::Request& req, roscpp::SetLoggerLevel::Response&)
00193 {
00194 log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(req.logger);
00195 log4cxx::LevelPtr level;
00196
00197 std::transform(req.level.begin(), req.level.end(), req.level.begin(), (int(*)(int))std::toupper);
00198
00199 if (req.level == "DEBUG")
00200 {
00201 level = log4cxx::Level::getDebug();
00202 }
00203 else if (req.level == "INFO")
00204 {
00205 level = log4cxx::Level::getInfo();
00206 }
00207 else if (req.level == "WARN")
00208 {
00209 level = log4cxx::Level::getWarn();
00210 }
00211 else if (req.level == "ERROR")
00212 {
00213 level = log4cxx::Level::getError();
00214 }
00215 else if (req.level == "FATAL")
00216 {
00217 level = log4cxx::Level::getFatal();
00218 }
00219
00220 if (level)
00221 {
00222 logger->setLevel(level);
00223 console::notifyLoggerLevelsChanged();
00224 return true;
00225 }
00226
00227 return false;
00228 }
00229
00230 bool closeAllConnections(roscpp::Empty::Request&, roscpp::Empty::Response&)
00231 {
00232 ROSCPP_LOG_DEBUG("close_all_connections service called, closing connections");
00233 ConnectionManager::instance()->clear(Connection::TransportDisconnect);
00234 return true;
00235 }
00236
00237 void clockCallback(const rosgraph_msgs::Clock::ConstPtr& msg)
00238 {
00239 Time::setNow(msg->clock);
00240 }
00241
00242 CallbackQueuePtr getInternalCallbackQueue()
00243 {
00244 if (!g_internal_callback_queue)
00245 {
00246 g_internal_callback_queue.reset(new CallbackQueue);
00247 }
00248
00249 return g_internal_callback_queue;
00250 }
00251
00252 void basicSigintHandler(int sig)
00253 {
00254 ros::requestShutdown();
00255 }
00256
00257 void internalCallbackQueueThreadFunc()
00258 {
00259 disableAllSignalsInThisThread();
00260
00261 CallbackQueuePtr queue = getInternalCallbackQueue();
00262
00263 while (!g_shutting_down)
00264 {
00265 queue->callAvailable(WallDuration(0.1));
00266 }
00267 }
00268
00269 bool isStarted()
00270 {
00271 return g_started;
00272 }
00273
00274 void start()
00275 {
00276 boost::mutex::scoped_lock lock(g_start_mutex);
00277 if (g_started)
00278 {
00279 return;
00280 }
00281
00282 g_shutdown_requested = false;
00283 g_shutting_down = false;
00284 g_started = true;
00285 g_ok = true;
00286
00287 bool enable_debug = false;
00288 const char* enable_debug_env = getenv("ROSCPP_ENABLE_DEBUG");
00289 if (enable_debug_env)
00290 {
00291 try
00292 {
00293 enable_debug = boost::lexical_cast<bool>(enable_debug_env);
00294 }
00295 catch (boost::bad_lexical_cast&)
00296 {
00297 }
00298 }
00299
00300 param::param("/tcp_keepalive", TransportTCP::s_use_keepalive_, TransportTCP::s_use_keepalive_);
00301
00302 PollManager::instance()->addPollThreadListener(checkForShutdown);
00303 XMLRPCManager::instance()->bind("shutdown", shutdownCallback);
00304
00305 initInternalTimerManager();
00306
00307 TopicManager::instance()->start();
00308 ServiceManager::instance()->start();
00309 ConnectionManager::instance()->start();
00310 PollManager::instance()->start();
00311 XMLRPCManager::instance()->start();
00312
00313 if (!(g_init_options & init_options::NoSigintHandler))
00314 {
00315 signal(SIGINT, basicSigintHandler);
00316 }
00317
00318 if (!(g_init_options & init_options::NoRosout))
00319 {
00320 g_rosout_appender = new ROSOutAppender;
00321 const log4cxx::LoggerPtr& logger = log4cxx::Logger::getLogger(ROSCONSOLE_ROOT_LOGGER_NAME);
00322 logger->addAppender(g_rosout_appender);
00323 }
00324
00325 if (g_shutting_down) goto end;
00326
00327 {
00328 ros::AdvertiseServiceOptions ops;
00329 ops.init<roscpp::GetLoggers>(names::resolve("~get_loggers"), getLoggers);
00330 ops.callback_queue = getInternalCallbackQueue().get();
00331 ServiceManager::instance()->advertiseService(ops);
00332 }
00333
00334 if (g_shutting_down) goto end;
00335
00336 {
00337 ros::AdvertiseServiceOptions ops;
00338 ops.init<roscpp::SetLoggerLevel>(names::resolve("~set_logger_level"), setLoggerLevel);
00339 ops.callback_queue = getInternalCallbackQueue().get();
00340 ServiceManager::instance()->advertiseService(ops);
00341 }
00342
00343 if (g_shutting_down) goto end;
00344
00345 if (enable_debug)
00346 {
00347 ros::AdvertiseServiceOptions ops;
00348 ops.init<roscpp::Empty>(names::resolve("~debug/close_all_connections"), closeAllConnections);
00349 ops.callback_queue = getInternalCallbackQueue().get();
00350 ServiceManager::instance()->advertiseService(ops);
00351 }
00352
00353 if (g_shutting_down) goto end;
00354
00355 {
00356 bool use_sim_time = false;
00357 param::param("/use_sim_time", use_sim_time, use_sim_time);
00358
00359 ros::Time::init();
00360
00361 if (use_sim_time)
00362 {
00363 Time::setNow(ros::Time());
00364 }
00365
00366 if (g_shutting_down) goto end;
00367
00368 if (use_sim_time)
00369 {
00370 ros::SubscribeOptions ops;
00371 ops.init<rosgraph_msgs::Clock>("/clock", 1, clockCallback);
00372 ops.callback_queue = getInternalCallbackQueue().get();
00373 TopicManager::instance()->subscribe(ops);
00374 }
00375 }
00376
00377 if (g_shutting_down) goto end;
00378
00379 g_internal_queue_thread = boost::thread(internalCallbackQueueThreadFunc);
00380 getGlobalCallbackQueue()->enable();
00381
00382 ROSCPP_LOG_DEBUG("Started node [%s], pid [%d], bound on [%s], xmlrpc port [%d], tcpros port [%d], logging to [%s], using [%s] time", this_node::getName().c_str(), getpid(), network::getHost().c_str(), XMLRPCManager::instance()->getServerPort(), ConnectionManager::instance()->getTCPPort(), file_log::getLogFilename().c_str(), Time::useSystemTime() ? "real" : "sim");
00383
00384
00385
00386 end:
00387
00388 if (g_shutting_down)
00389 {
00390 boost::recursive_mutex::scoped_lock lock(g_shutting_down_mutex);
00391 }
00392 }
00393
00394 void init(const M_string& remappings, const std::string& name, uint32_t options)
00395 {
00396 if (!g_atexit_registered)
00397 {
00398 g_atexit_registered = true;
00399 atexit(atexitCallback);
00400 }
00401
00402 if (!g_global_queue)
00403 {
00404 g_global_queue.reset(new CallbackQueue);
00405 }
00406
00407 if (!g_initialized)
00408 {
00409 g_init_options = options;
00410 g_ok = true;
00411
00412 ROSCONSOLE_AUTOINIT;
00413
00414 signal(SIGPIPE, SIG_IGN);
00415 network::init(remappings);
00416 master::init(remappings);
00417
00418 this_node::init(name, remappings, options);
00419 file_log::init(remappings);
00420 param::init(remappings);
00421
00422 g_initialized = true;
00423 }
00424 }
00425
00426 void init(int& argc, char** argv, const std::string& name, uint32_t options)
00427 {
00428 M_string remappings;
00429
00430 int full_argc = argc;
00431
00432 for (int i = 0; i < argc; )
00433 {
00434 std::string arg = argv[i];
00435 size_t pos = arg.find(":=");
00436 if (pos != std::string::npos)
00437 {
00438 std::string local_name = arg.substr(0, pos);
00439 std::string external_name = arg.substr(pos + 2);
00440
00441 remappings[local_name] = external_name;
00442
00443
00444 char *tmp = argv[i];
00445 for (int j = i; j < full_argc - 1; j++)
00446 argv[j] = argv[j+1];
00447 argv[argc-1] = tmp;
00448 argc--;
00449 }
00450 else
00451 {
00452 i++;
00453 }
00454 }
00455
00456 init(remappings, name, options);
00457 }
00458
00459 void init(const VP_string& remappings, const std::string& name, uint32_t options)
00460 {
00461 M_string remappings_map;
00462 VP_string::const_iterator it = remappings.begin();
00463 VP_string::const_iterator end = remappings.end();
00464 for (; it != end; ++it)
00465 {
00466 remappings_map[it->first] = it->second;
00467 }
00468
00469 init(remappings_map, name, options);
00470 }
00471
00472 void removeROSArgs(int argc, const char* const* argv, V_string& args_out)
00473 {
00474 for (int i = 0; i < argc; ++i)
00475 {
00476 std::string arg = argv[i];
00477 size_t pos = arg.find(":=");
00478 if (pos == std::string::npos)
00479 {
00480 args_out.push_back(arg);
00481 }
00482 }
00483 }
00484
00485 void spin()
00486 {
00487 SingleThreadedSpinner s;
00488 spin(s);
00489 }
00490
00491 void spin(Spinner& s)
00492 {
00493 s.spin();
00494 }
00495
00496 void spinOnce()
00497 {
00498 g_global_queue->callAvailable(ros::WallDuration());
00499 }
00500
00501 void waitForShutdown()
00502 {
00503 while (ok())
00504 {
00505 WallDuration(0.05).sleep();
00506 }
00507 }
00508
00509 CallbackQueue* getGlobalCallbackQueue()
00510 {
00511 return g_global_queue.get();
00512 }
00513
00514 bool ok()
00515 {
00516 return g_ok;
00517 }
00518
00519 void shutdown()
00520 {
00521 boost::recursive_mutex::scoped_lock lock(g_shutting_down_mutex);
00522 if (g_shutting_down)
00523 return;
00524 else
00525 g_shutting_down = true;
00526
00527 ROSCPP_LOG_DEBUG("Shutting down roscpp");
00528
00529 g_global_queue->disable();
00530 g_global_queue->clear();
00531
00532 if (g_internal_queue_thread.get_id() != boost::this_thread::get_id())
00533 {
00534 g_internal_queue_thread.join();
00535 }
00536
00537 const log4cxx::LoggerPtr& logger =
00538 log4cxx::Logger::getLogger(ROSCONSOLE_ROOT_LOGGER_NAME);
00539 logger->removeAppender(g_rosout_appender);
00540 g_rosout_appender = 0;
00541
00542 if (g_started)
00543 {
00544 TopicManager::instance()->shutdown();
00545 ServiceManager::instance()->shutdown();
00546 PollManager::instance()->shutdown();
00547 ConnectionManager::instance()->shutdown();
00548 XMLRPCManager::instance()->shutdown();
00549 }
00550
00551 WallTime end = WallTime::now();
00552
00553 g_started = false;
00554 g_ok = false;
00555 Time::shutdown();
00556
00557
00558
00559
00560
00561
00562 log4cxx::Logger::getRootLogger()->getLoggerRepository()->shutdown();
00563 ros::console::shutdown();
00564 log4cxx::LoggerPtr& fo_logger = ros::file_log::getFileOnlyLogger();
00565 fo_logger = log4cxx::LoggerPtr();
00566 }
00567
00568 }