ros::init(argc,argv,"amcl");
init.h分析:
#ifndef ROSCPP_INIT_H
#define ROSCPP_INIT_H
#include "ros/forwards.h"
#include "ros/spinner.h"
#include "common.h"
namespace ros
{
namespace init_options
{
/**
* \brief Flags for ROS initialization
*/
enum InitOption
{
/**
* Don't install a SIGINT handler. You should install your own SIGINT handler in this
* case, to ensure that the node gets shutdown correctly when it exits.
*/
NoSigintHandler = 1 << 0,//以1二进制左移0位
/** \brief Anonymize the node name. Adds a random number to the end of your node's name, to make it unique.
*/
AnonymousName = 1 << 1,
/**
* \brief Don't broadcast rosconsole output to the /rosout topic
*/
NoRosout = 1 << 2,
};
}
typedef init_options::InitOption InitOption;
/** @brief ROS initialization function.
*
* This function will parse any ROS arguments (e.g., topic name
* remappings), and will consume them (i.e., argc and argv may be modified
* as a result of this call).
*
* Use this version if you are using the NodeHandle API
*
* \param argc
* \param argv
* \param name Name of this node. The name must be a base name, ie. it cannot contain namespaces.
* \param options [optional] Options to start the node with (a set of bit flags from \ref ros::init_options)
* \throws InvalidNodeNameException If the name passed in is not a valid "base" name
*
*/
ROSCPP_DECL void init(int &argc, char **argv, const std::string& name, uint32_t options = 0);
/**
* \brief alternate ROS initialization function.
*
* \param remappings A map<string, string> where each one constitutes a name remapping, or one of the special remappings like __name, __master, __ns, etc.
* \param name Name of this node. The name must be a base name, ie. it cannot contain namespaces.
* \param options [optional] Options to start the node with (a set of bit flags from \ref ros::init_options)
* \throws InvalidNodeNameException If the name passed in is not a valid "base" name
*/
ROSCPP_DECL void init(const M_string& remappings, const std::string& name, uint32_t options = 0);
/**
* \brief alternate ROS initialization function.
*
* \param remappings A vectorstring, string> > where each one constitutes a name remapping, or one of the special remappings like __name, __master, __ns, etc.
* \param name Name of this node. The name must be a base name, ie. it cannot contain namespaces.
* \param options [optional] Options to start the node with (a set of bit flags from \ref ros::init_options)
* \throws InvalidNodeNameException If the name passed in is not a valid "base" name
*/
ROSCPP_DECL void init(const VP_string& remapping_args, const std::string& name, uint32_t options = 0);
/**
* \brief Returns whether or not ros::init() has been called
*/
ROSCPP_DECL bool isInitialized();
/**
* \brief Returns whether or not ros::shutdown() has been (or is being) called
*/
ROSCPP_DECL bool isShuttingDown();
/** \brief Enter simple event loop
*
* This method enters a loop, processing callbacks. This method should only be used
* if the NodeHandle API is being used.
*
* This method is mostly useful when your node does all of its work in
* subscription callbacks. It will not process any callbacks that have been assigned to
* custom queues.
*
*/
ROSCPP_DECL void spin();
/** \brief Enter simple event loop
*
* This method enters a loop, processing callbacks. This method should only be used
* if the NodeHandle API is being used.
*
* This method is mostly useful when your node does all of its work in
* subscription callbacks. It will not process any callbacks that have been assigned to
* custom queues.
*
* \param spinner a spinner to use to call callbacks. Two default implementations are available,
* SingleThreadedSpinner and MultiThreadedSpinner
*/
ROSCPP_DECL void spin(Spinner& spinner);
/**
* \brief Process a single round of callbacks.
*
* This method is useful if you have your own loop running and would like to process
* any callbacks that are available. This is equivalent to calling callAvailable() on the
* global CallbackQueue. It will not process any callbacks that have been assigned to
* custom queues.
*/
ROSCPP_DECL void spinOnce();
/**
* \brief Wait for this node to be shutdown, whether through Ctrl-C, ros::shutdown(), or similar.
*/
ROSCPP_DECL void waitForShutdown();
/** \brief Check whether it's time to exit.
*
* ok() becomes false once ros::shutdown() has been called and is finished
*
* \return true if we're still OK, false if it's time to exit
*/
ROSCPP_DECL bool ok();
/**
* \brief Disconnects everything and unregisters from the master. It is generally not
* necessary to call this function, as the node will automatically shutdown when all
* NodeHandles destruct. However, if you want to break out of a spin() loop explicitly,
* this function allows that.
*/
ROSCPP_DECL void shutdown();
/**
* \brief Request that the node shut itself down from within a ROS thread
*
* This method signals a ROS thread to call shutdown().
*/
ROSCPP_DECL void requestShutdown();
/**
* \brief Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc loops,
* connects to internal subscriptions like /clock, starts internal service servers, etc.).
*
* Usually unnecessary to call manually, as it is automatically called by the creation of the first NodeHandle if
* the node has not already been started. If you would like to prevent the automatic shutdown caused by the last
* NodeHandle going out of scope, call this before any NodeHandle has been created (e.g. immediately after init())
*/
ROSCPP_DECL void start();
/**
* \brief Returns whether or not the node has been started through ros::start()
*/
ROSCPP_DECL bool isStarted();
/**
* \brief Returns a pointer to the global default callback queue.
*
* This is the queue that all callbacks get added to unless a different one is specified, either in the NodeHandle
* or in the individual NodeHandle::subscribe()/NodeHandle::advertise()/etc. functions.
*/
ROSCPP_DECL CallbackQueue* getGlobalCallbackQueue();
/**
* \brief searches the command line arguments for the given arg parameter. In case this argument is not found
* an empty string is returned.
*
* \param argc the number of command-line arguments
* \param argv the command-line arguments
* \param arg argument to search for
*/
ROSCPP_DECL std::string getROSArg(int argc, const char* const* argv, const std::string& arg);
/**
* \brief returns a vector of program arguments that do not include any ROS remapping arguments. Useful if you need
* to parse your arguments to determine your node name
*
* \param argc the number of command-line arguments
* \param argv the command-line arguments
* \param [out] args_out Output args, stripped of any ROS args
*/
ROSCPP_DECL void removeROSArgs(int argc, const char* const* argv, V_string& args_out);
}
#endif
init.cpp源码待分析
#include "ros/init.h"
#include "ros/names.h"
#include "ros/xmlrpc_manager.h"
#include "ros/poll_manager.h"
#include "ros/connection_manager.h"
#include "ros/topic_manager.h"
#include "ros/service_manager.h"
#include "ros/this_node.h"
#include "ros/network.h"
#include "ros/file_log.h"
#include "ros/callback_queue.h"
#include "ros/param.h"
#include "ros/rosout_appender.h"
#include "ros/subscribe_options.h"
#include "ros/transport/transport_tcp.h"
#include "ros/internal_timer_manager.h"
#include "xmlrpcpp/XmlRpcSocket.h"
#include "roscpp/GetLoggers.h"
#include "roscpp/SetLoggerLevel.h"
#include "roscpp/Empty.h"
#include
#include
#include
#include
#include
#include
namespace ros
{
namespace master
{
void init(const M_string& remappings);
}
namespace this_node
{
void init(const std::string& names, const M_string& remappings, uint32_t options);
}
namespace network
{
void init(const M_string& remappings);
}
namespace param
{
void init(const M_string& remappings);
}
namespace file_log
{
void init(const M_string& remappings);
}
CallbackQueuePtr g_global_queue;
ROSOutAppender* g_rosout_appender;
static CallbackQueuePtr g_internal_callback_queue;
static bool g_initialized = false;
static bool g_started = false;
static bool g_atexit_registered = false;
static boost::mutex g_start_mutex;
static bool g_ok = false;
static uint32_t g_init_options = 0;
static bool g_shutdown_requested = false;
static volatile bool g_shutting_down = false;
static boost::recursive_mutex g_shutting_down_mutex;
static boost::thread g_internal_queue_thread;
bool isInitialized()
{
return g_initialized;
}
bool isShuttingDown()
{
return g_shutting_down;
}
void checkForShutdown()
{
if (g_shutdown_requested)
{
// Since this gets run from within a mutex inside PollManager, we need to prevent ourselves from deadlocking with
// another thread that's already in the middle of shutdown()
boost::recursive_mutex::scoped_try_lock lock(g_shutting_down_mutex, boost::defer_lock);
while (!lock.try_lock() && !g_shutting_down)
{
ros::WallDuration(0.001).sleep();
}
if (!g_shutting_down)
{
shutdown();
}
g_shutdown_requested = false;
}
}
void requestShutdown()
{
g_shutdown_requested = true;
}
void atexitCallback()
{
if (ok() && !isShuttingDown())
{
ROSCPP_LOG_DEBUG("shutting down due to exit() or end of main() without cleanup of all NodeHandles");
g_started = false; // don't shutdown singletons, because they are already destroyed
shutdown();
}
}
void shutdownCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
{
int num_params = 0;
if (params.getType() == XmlRpc::XmlRpcValue::TypeArray)
num_params = params.size();
if (num_params > 1)
{
std::string reason = params[1];
ROS_WARN("Shutdown request received.");
ROS_WARN("Reason given for shutdown: [%s]", reason.c_str());
requestShutdown();
}
result = xmlrpc::responseInt(1, "", 0);
}
bool getLoggers(roscpp::GetLoggers::Request&, roscpp::GetLoggers::Response& resp)
{
std::map<std::string, ros::console::levels::Level> loggers;
bool success = ::ros::console::get_loggers(loggers);
if (success)
{
for (std::map<std::string, ros::console::levels::Level>::const_iterator it = loggers.begin(); it != loggers.end(); it++)
{
roscpp::Logger logger;
logger.name = it->first;
ros::console::levels::Level level = it->second;
if (level == ros::console::levels::Debug)
{
logger.level = "debug";
}
else if (level == ros::console::levels::Info)
{
logger.level = "info";
}
else if (level == ros::console::levels::Warn)
{
logger.level = "warn";
}
else if (level == ros::console::levels::Error)
{
logger.level = "error";
}
else if (level == ros::console::levels::Fatal)
{
logger.level = "fatal";
}
resp.loggers.push_back(logger);
}
}
return success;
}
bool setLoggerLevel(roscpp::SetLoggerLevel::Request& req, roscpp::SetLoggerLevel::Response&)
{
std::transform(req.level.begin(), req.level.end(), req.level.begin(), (int(*)(int))std::toupper);
ros::console::levels::Level level;
if (req.level == "DEBUG")
{
level = ros::console::levels::Debug;
}
else if (req.level == "INFO")
{
level = ros::console::levels::Info;
}
else if (req.level == "WARN")
{
level = ros::console::levels::Warn;
}
else if (req.level == "ERROR")
{
level = ros::console::levels::Error;
}
else if (req.level == "FATAL")
{
level = ros::console::levels::Fatal;
}
else
{
return false;
}
bool success = ::ros::console::set_logger_level(req.logger, level);
if (success)
{
console::notifyLoggerLevelsChanged();
}
return success;
}
bool closeAllConnections(roscpp::Empty::Request&, roscpp::Empty::Response&)
{
ROSCPP_LOG_DEBUG("close_all_connections service called, closing connections");
ConnectionManager::instance()->clear(Connection::TransportDisconnect);
return true;
}
void clockCallback(const rosgraph_msgs::Clock::ConstPtr& msg)
{
Time::setNow(msg->clock);
}
CallbackQueuePtr getInternalCallbackQueue()
{
if (!g_internal_callback_queue)
{
g_internal_callback_queue.reset(new CallbackQueue);
}
return g_internal_callback_queue;
}
void basicSigintHandler(int sig)
{
(void)sig;
ros::requestShutdown();
}
void internalCallbackQueueThreadFunc()
{
disableAllSignalsInThisThread();
CallbackQueuePtr queue = getInternalCallbackQueue();
while (!g_shutting_down)
{
queue->callAvailable(WallDuration(0.1));
}
}
bool isStarted()
{
return g_started;
}
void start()
{
boost::mutex::scoped_lock lock(g_start_mutex);
if (g_started)
{
return;
}
g_shutdown_requested = false;
g_shutting_down = false;
g_started = true;
g_ok = true;
bool enable_debug = false;
std::string enable_debug_env;
if ( get_environment_variable(enable_debug_env,"ROSCPP_ENABLE_DEBUG") )
{
try
{
enable_debug = boost::lexical_cast<bool>(enable_debug_env.c_str());
}
catch (boost::bad_lexical_cast&)
{
}
}
char* env_ipv6 = NULL;
#ifdef _MSC_VER
_dupenv_s(&env_ipv6, NULL, "ROS_IPV6");
#else
env_ipv6 = getenv("ROS_IPV6");
#endif
bool use_ipv6 = (env_ipv6 && strcmp(env_ipv6,"on") == 0);
TransportTCP::s_use_ipv6_ = use_ipv6;
XmlRpc::XmlRpcSocket::s_use_ipv6_ = use_ipv6;
#ifdef _MSC_VER
if (env_ipv6)
{
free(env_ipv6);
}
#endif
param::param("/tcp_keepalive", TransportTCP::s_use_keepalive_, TransportTCP::s_use_keepalive_);
PollManager::instance()->addPollThreadListener(checkForShutdown);
XMLRPCManager::instance()->bind("shutdown", shutdownCallback);
initInternalTimerManager();
TopicManager::instance()->start();
ServiceManager::instance()->start();
ConnectionManager::instance()->start();
PollManager::instance()->start();
XMLRPCManager::instance()->start();
if (!(g_init_options & init_options::NoSigintHandler))
{
signal(SIGINT, basicSigintHandler);
}
ros::Time::init();
if (!(g_init_options & init_options::NoRosout))
{
g_rosout_appender = new ROSOutAppender;
ros::console::register_appender(g_rosout_appender);
}
if (g_shutting_down) goto end;
{
ros::AdvertiseServiceOptions ops;
ops.init(names::resolve("~get_loggers"), getLoggers);
ops.callback_queue = getInternalCallbackQueue().get();
ServiceManager::instance()->advertiseService(ops);
}
if (g_shutting_down) goto end;
{
ros::AdvertiseServiceOptions ops;
ops.init(names::resolve("~set_logger_level"), setLoggerLevel);
ops.callback_queue = getInternalCallbackQueue().get();
ServiceManager::instance()->advertiseService(ops);
}
if (g_shutting_down) goto end;
if (enable_debug)
{
ros::AdvertiseServiceOptions ops;
ops.init(names::resolve("~debug/close_all_connections"), closeAllConnections);
ops.callback_queue = getInternalCallbackQueue().get();
ServiceManager::instance()->advertiseService(ops);
}
if (g_shutting_down) goto end;
{
bool use_sim_time = false;
param::param("/use_sim_time", use_sim_time, use_sim_time);
if (use_sim_time)
{
Time::setNow(ros::Time());
}
if (g_shutting_down) goto end;
if (use_sim_time)
{
ros::SubscribeOptions ops;
ops.init(names::resolve("/clock"), 1, clockCallback);
ops.callback_queue = getInternalCallbackQueue().get();
TopicManager::instance()->subscribe(ops);
}
}
if (g_shutting_down) goto end;
g_internal_queue_thread = boost::thread(internalCallbackQueueThreadFunc);
getGlobalCallbackQueue()->enable();
ROSCPP_LOG_DEBUG("Started node [%s], pid [%d], bound on [%s], xmlrpc port [%d], tcpros port [%d], using [%s] time",
this_node::getName().c_str(), getpid(), network::getHost().c_str(),
XMLRPCManager::instance()->getServerPort(), ConnectionManager::instance()->getTCPPort(),
Time::useSystemTime() ? "real" : "sim");
// Label used to abort if we've started shutting down in the middle of start(), which can happen in
// threaded code or if Ctrl-C is pressed while we're initializing
end:
// If we received a shutdown request while initializing, wait until we've shutdown to continue
if (g_shutting_down)
{
boost::recursive_mutex::scoped_lock lock(g_shutting_down_mutex);
}
}
void init(const M_string& remappings, const std::string& name, uint32_t options)
{
if (!g_atexit_registered)
{
g_atexit_registered = true;
atexit(atexitCallback);
}
if (!g_global_queue)
{
g_global_queue.reset(new CallbackQueue);
}
if (!g_initialized)
{
g_init_options = options;
g_ok = true;
ROSCONSOLE_AUTOINIT;
// Disable SIGPIPE
#ifndef WIN32
signal(SIGPIPE, SIG_IGN);
#endif
network::init(remappings);
master::init(remappings);
// names:: namespace is initialized by this_node
this_node::init(name, remappings, options);
file_log::init(remappings);
param::init(remappings);
g_initialized = true;
}
}
void init(int& argc, char** argv, const std::string& name, uint32_t options)
{
M_string remappings;
int full_argc = argc;
// now, move the remapping argv's to the end, and decrement argc as needed
for (int i = 0; i < argc; )
{
std::string arg = argv[i];
size_t pos = arg.find(":=");
if (pos != std::string::npos)
{
std::string local_name = arg.substr(0, pos);
std::string external_name = arg.substr(pos + 2);
ROSCPP_LOG_DEBUG("remap: %s => %s", local_name.c_str(), external_name.c_str());
remappings[local_name] = external_name;
// shuffle everybody down and stuff this guy at the end of argv
char *tmp = argv[i];
for (int j = i; j < full_argc - 1; j++)
argv[j] = argv[j+1];
argv[argc-1] = tmp;
argc--;
}
else
{
i++; // move on, since we didn't shuffle anybody here to replace it
}
}
init(remappings, name, options);
}
void init(const VP_string& remappings, const std::string& name, uint32_t options)
{
M_string remappings_map;
VP_string::const_iterator it = remappings.begin();
VP_string::const_iterator end = remappings.end();
for (; it != end; ++it)
{
remappings_map[it->first] = it->second;
}
init(remappings_map, name, options);
}
std::string getROSArg(int argc, const char* const* argv, const std::string& arg)
{
for (int i = 0; i < argc; ++i)
{
std::string str_arg = argv[i];
size_t pos = str_arg.find(":=");
if (str_arg.substr(0,pos) == arg)
{
return str_arg.substr(pos+2);
}
}
return "";
}
void removeROSArgs(int argc, const char* const* argv, V_string& args_out)
{
for (int i = 0; i < argc; ++i)
{
std::string arg = argv[i];
size_t pos = arg.find(":=");
if (pos == std::string::npos)
{
args_out.push_back(arg);
}
}
}
void spin()
{
SingleThreadedSpinner s;
spin(s);
}
void spin(Spinner& s)
{
s.spin();
}
void spinOnce()
{
g_global_queue->callAvailable(ros::WallDuration());
}
void waitForShutdown()
{
while (ok())
{
WallDuration(0.05).sleep();
}
}
CallbackQueue* getGlobalCallbackQueue()
{
return g_global_queue.get();
}
bool ok()
{
return g_ok;
}
void shutdown()
{
boost::recursive_mutex::scoped_lock lock(g_shutting_down_mutex);
if (g_shutting_down)
return;
else
g_shutting_down = true;
ros::console::shutdown();
g_global_queue->disable();
g_global_queue->clear();
if (g_internal_queue_thread.get_id() != boost::this_thread::get_id())
{
g_internal_queue_thread.join();
}
g_rosout_appender = 0;
if (g_started)
{
TopicManager::instance()->shutdown();
ServiceManager::instance()->shutdown();
PollManager::instance()->shutdown();
ConnectionManager::instance()->shutdown();
XMLRPCManager::instance()->shutdown();
}
WallTime end = WallTime::now();
g_started = false;
g_ok = false;
Time::shutdown();
}
}
***Q :1.ROSCPP DECL ??
A :common.h 中*
#ifndef ROSCPP_COMMON_H
#define ROSCPP_COMMON_H
#include
#include
#include
#include
#include "ros/assert.h"
#include "ros/forwards.h"
#include "ros/serialized_message.h"
#include
#define ROS_VERSION_MAJOR 1
#define ROS_VERSION_MINOR 12
#define ROS_VERSION_PATCH 7
#define ROS_VERSION_COMBINED(major, minor, patch) (((major) << 20) | ((minor) << 10) | (patch))
#define ROS_VERSION ROS_VERSION_COMBINED(ROS_VERSION_MAJOR, ROS_VERSION_MINOR, ROS_VERSION_PATCH)
#define ROS_VERSION_GE(major1, minor1, patch1, major2, minor2, patch2) (ROS_VERSION_COMBINED(major1, minor1, patch1) >= ROS_VERSION_COMBINED(major2, minor2, patch2))
#define ROS_VERSION_MINIMUM(major, minor, patch) ROS_VERSION_GE(ROS_VERSION_MAJOR, ROS_VERSION_MINOR, ROS_VERSION_PATCH, major, minor, patch)
#include
// Import/export for windows dll's and visibility for gcc shared libraries.
#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
#ifdef roscpp_EXPORTS // we are building a shared lib/dll
#define ROSCPP_DECL ROS_HELPER_EXPORT
#else // we are using shared lib/dll
**#define ROSCPP_DECL ROS_HELPER_IMPORT**
#endif
ROS_HELPER_IMPORT在macros.h中如下:
#ifndef ROSLIB_MACROS_H_INCLUDED
#define ROSLIB_MACROS_H_INCLUDED
#if defined(__GNUC__)
#define ROS_DEPRECATED __attribute__((deprecated))
#define ROS_FORCE_INLINE __attribute__((always_inline))
#elif defined(_MSC_VER)
#define ROS_DEPRECATED
#define ROS_FORCE_INLINE __forceinline
#else
#define ROS_DEPRECATED
#define ROS_FORCE_INLINE inline
#endif
/*
Windows import/export and gnu http://gcc.gnu.org/wiki/Visibility
macros.
*/
#if defined(_MSC_VER)
#define ROS_HELPER_IMPORT __declspec(dllimport)
#define ROS_HELPER_EXPORT __declspec(dllexport)
#define ROS_HELPER_LOCAL
#elif __GNUC__ >= 4
#define ROS_HELPER_IMPORT __attribute__ ((visibility("default"))) //待深究。。。
[http://blog.csdn.net/kevin_android_123456/article/details/6982481](http://blog.csdn.net/kevin_android_123456/article/details/6982481)
#define ROS_HELPER_EXPORT __attribute__ ((visibility("default")))
#define ROS_HELPER_LOCAL __attribute__ ((visibility("hidden")))
#else
#define ROS_HELPER_IMPORT
#define ROS_HELPER_EXPORT
#define ROS_HELPER_LOCAL
#endif
// Ignore warnings about import/exports when deriving from std classes.
#ifdef _MSC_VER
#pragma warning(disable: 4251)
#pragma warning(disable: 4275)
#endif
#endif
#else // ros is being built around static libraries
#define ROSCPP_DECL
#endif
namespace ros
{
void disableAllSignalsInThisThread();
}
#endif
Q 2:为什么有很多init函数?
A 2:
init.cpp中:
void init(const M_string& remappings, const std::string& name, uint32_t options)
{
if (!g_atexit_registered)
{
g_atexit_registered = true;
atexit(atexitCallback);
}
if (!g_global_queue)
{
g_global_queue.reset(new CallbackQueue);
}
if (!g_initialized)
{
g_init_options = options;
g_ok = true;
ROSCONSOLE_AUTOINIT;
// Disable SIGPIPE
#ifndef WIN32
signal(SIGPIPE, SIG_IGN);
#endif
network::init(remappings);
master::init(remappings);
// names:: namespace is initialized by this_node
this_node::init(name, remappings, options);
file_log::init(remappings);
param::init(remappings);
g_initialized = true;
}
}
void init(int& argc, char** argv, const std::string& name, uint32_t options)
{
M_string remappings;
int full_argc = argc;
// now, move the remapping argv's to the end, and decrement argc as needed
for (int i = 0; i < argc; )
{
std::string arg = argv[i];
size_t pos = arg.find(":=");
if (pos != std::string::npos)
{
std::string local_name = arg.substr(0, pos);
std::string external_name = arg.substr(pos + 2);
ROSCPP_LOG_DEBUG("remap: %s => %s", local_name.c_str(), external_name.c_str());
remappings[local_name] = external_name;
// shuffle everybody down and stuff this guy at the end of argv
char *tmp = argv[i];
for (int j = i; j < full_argc - 1; j++)
argv[j] = argv[j+1];
argv[argc-1] = tmp;
argc--;
}
else
{
i++; // move on, since we didn't shuffle anybody here to replace it
}
}
init(remappings, name, options);
}
void init(const VP_string& remappings, const std::string& name, uint32_t options)
{
M_string remappings_map;
VP_string::const_iterator it = remappings.begin();
VP_string::const_iterator end = remappings.end();
for (; it != end; ++it)
{
remappings_map[it->first] = it->second;
}
init(remappings_map, name, options);
}
只有第一个init起作用,其余两个都是传入参数到第一个init函数。然后初始化master和network,具体以后分析。。
Q 3 :参数问题:
A 3 :http://ju.outofmemory.cn/entry/113955
???roscpp does not try to specify a threading model for your application. This means that while roscpp may use threads behind the scenes to do network management, scheduling etc., it will never expose its threads to your application. roscpp does, however, allow your callbacks to be called from any number of threads if that’s what you want.
network.cpp network::init(remapping);
#include "config.h"
#include "ros/network.h"
#include "ros/file_log.h"
#include "ros/exceptions.h"
#include "ros/io.h" // cross-platform headers needed
#include
#include
#ifdef HAVE_IFADDRS_H
#include
#endif
#include
namespace ros
{
namespace network
{
std::string g_host;
uint16_t g_tcpros_server_port = 0;
const std::string& getHost()
{
return g_host;
}
bool splitURI(const std::string& uri, std::string& host, uint32_t& port)
{
// skip over the protocol if it's there
if (uri.substr(0, 7) == std::string("http://"))
host = uri.substr(7);
else if (uri.substr(0, 9) == std::string("rosrpc://"))
host = uri.substr(9);
// split out the port
std::string::size_type colon_pos = host.find_first_of(":");
if (colon_pos == std::string::npos)
return false;
std::string port_str = host.substr(colon_pos+1);
std::string::size_type slash_pos = port_str.find_first_of("/");
if (slash_pos != std::string::npos)
port_str = port_str.erase(slash_pos);
port = atoi(port_str.c_str());
host = host.erase(colon_pos);
return true;
}
uint16_t getTCPROSPort()
{
return g_tcpros_server_port;
}
static bool isPrivateIP(const char *ip)
{
bool b = !strncmp("192.168", ip, 7) || !strncmp("10.", ip, 3) ||
!strncmp("169.254", ip, 7);
return b;
}
std::string determineHost()
{
std::string ip_env;
// First, did the user set ROS_HOSTNAME?
if ( get_environment_variable(ip_env, "ROS_HOSTNAME")) {
ROSCPP_LOG_DEBUG( "determineIP: using value of ROS_HOSTNAME:%s:", ip_env.c_str());
if (ip_env.size() == 0)
{
ROS_WARN("invalid ROS_HOSTNAME (an empty string)");
}
return ip_env;
}
// Second, did the user set ROS_IP?
if ( get_environment_variable(ip_env, "ROS_IP")) {
ROSCPP_LOG_DEBUG( "determineIP: using value of ROS_IP:%s:", ip_env.c_str());
if (ip_env.size() == 0)
{
ROS_WARN("invalid ROS_IP (an empty string)");
}
return ip_env;
}
// Third, try the hostname
char host[1024];
memset(host,0,sizeof(host));
if(gethostname(host,sizeof(host)-1) != 0)
{
ROS_ERROR("determineIP: gethostname failed");
}
// We don't want localhost to be our ip
else if(strlen(host) && strcmp("localhost", host))
{
return std::string(host);
}
// Fourth, fall back on interface search, which will yield an IP address
#ifdef HAVE_IFADDRS_H
struct ifaddrs *ifa = NULL, *ifp = NULL;
int rc;
if ((rc = getifaddrs(&ifp)) < 0)
{
ROS_FATAL("error in getifaddrs: [%s]", strerror(rc));
ROS_BREAK();
}
char preferred_ip[200] = {0};
for (ifa = ifp; ifa; ifa = ifa->ifa_next)
{
char ip_[200];
socklen_t salen;
if (!ifa->ifa_addr)
continue; // evidently this interface has no ip address
if (ifa->ifa_addr->sa_family == AF_INET)
salen = sizeof(struct sockaddr_in);
else if (ifa->ifa_addr->sa_family == AF_INET6)
salen = sizeof(struct sockaddr_in6);
else
continue;
if (getnameinfo(ifa->ifa_addr, salen, ip_, sizeof(ip_), NULL, 0,
NI_NUMERICHOST) < 0)
{
ROSCPP_LOG_DEBUG( "getnameinfo couldn't get the ip of interface [%s]", ifa->ifa_name);
continue;
}
//ROS_INFO( "ip of interface [%s] is [%s]", ifa->ifa_name, ip);
// prefer non-private IPs over private IPs
if (!strcmp("127.0.0.1", ip_) || strchr(ip_,':'))
continue; // ignore loopback unless we have no other choice
if (ifa->ifa_addr->sa_family == AF_INET6 && !preferred_ip[0])
strcpy(preferred_ip, ip_);
else if (isPrivateIP(ip_) && !preferred_ip[0])
strcpy(preferred_ip, ip_);
else if (!isPrivateIP(ip_) &&
(isPrivateIP(preferred_ip) || !preferred_ip[0]))
strcpy(preferred_ip, ip_);
}
freeifaddrs(ifp);
if (!preferred_ip[0])
{
ROS_ERROR( "Couldn't find a preferred IP via the getifaddrs() call; I'm assuming that your IP "
"address is 127.0.0.1. This should work for local processes, "
"but will almost certainly not work if you have remote processes."
"Report to the ROS development team to seek a fix.");
return std::string("127.0.0.1");
}
ROSCPP_LOG_DEBUG( "preferred IP is guessed to be %s", preferred_ip);
return std::string(preferred_ip);
#else
// @todo Fix IP determination in the case where getifaddrs() isn't
// available.
ROS_ERROR( "You don't have the getifaddrs() call; I'm assuming that your IP "
"address is 127.0.0.1. This should work for local processes, "
"but will almost certainly not work if you have remote processes."
"Report to the ROS development team to seek a fix.");
return std::string("127.0.0.1");
#endif
}
void init(const M_string& remappings)
{
M_string::const_iterator it = remappings.find("__hostname");
if (it != remappings.end())
{
g_host = it->second;
}
else
{
it = remappings.find("__ip");
if (it != remappings.end())
{
g_host = it->second;
}
}
it = remappings.find("__tcpros_server_port");
if (it != remappings.end())
{
try
{
g_tcpros_server_port = boost::lexical_cast(it->second);
}
catch (boost::bad_lexical_cast&)
{
throw ros::InvalidPortException("__tcpros_server_port [" + it->second + "] was not specified as a number within the 0-65535 range");
}
}
if (g_host.empty())
{
g_host = determineHost();
}
}
} // namespace network
} // namespace ros