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