Go to the documentation of this file.
53 #include "roscpp/GetLoggers.h"
54 #include "roscpp/SetLoggerLevel.h"
55 #include "roscpp/Empty.h"
59 #include <rosgraph_msgs/Clock.h>
77 void init(
const std::string& names,
const M_string& remappings, uint32_t options);
151 ROSCPP_LOG_DEBUG(
"shutting down due to exit() or end of main() without cleanup of all NodeHandles");
161 num_params = params.
size();
164 std::string reason = params[1];
165 ROS_WARN(
"Shutdown request received.");
166 ROS_WARN(
"Reason given for shutdown: [%s]", reason.c_str());
173 bool getLoggers(roscpp::GetLoggers::Request&, roscpp::GetLoggers::Response& resp)
175 std::map<std::string, ros::console::levels::Level> loggers;
176 bool success = ::ros::console::get_loggers(loggers);
179 for (std::map<std::string, ros::console::levels::Level>::const_iterator it = loggers.begin(); it != loggers.end(); it++)
181 roscpp::Logger logger;
182 logger.name = it->first;
186 logger.level =
"debug";
190 logger.level =
"info";
194 logger.level =
"warn";
198 logger.level =
"error";
202 logger.level =
"fatal";
204 resp.loggers.push_back(logger);
210 bool setLoggerLevel(roscpp::SetLoggerLevel::Request& req, roscpp::SetLoggerLevel::Response&)
212 std::transform(req.level.begin(), req.level.end(), req.level.begin(), (
int(*)(
int))std::toupper);
215 if (req.level ==
"DEBUG")
219 else if (req.level ==
"INFO")
223 else if (req.level ==
"WARN")
227 else if (req.level ==
"ERROR")
231 else if (req.level ==
"FATAL")
240 bool success = ::ros::console::set_logger_level(req.logger, level);
251 ROSCPP_LOG_DEBUG(
"close_all_connections service called, closing connections");
279 disableAllSignalsInThisThread();
307 bool enable_debug =
false;
308 std::string enable_debug_env;
313 enable_debug = boost::lexical_cast<bool>(enable_debug_env.c_str());
315 catch (boost::bad_lexical_cast&)
340 bool no_rosout =
false;
341 std::string no_rosout_env;
346 no_rosout = boost::lexical_cast<bool>(no_rosout_env.c_str());
348 catch (boost::bad_lexical_cast&)
390 bool use_sim_time =
false;
393 param::param(
"/use_sim_time", use_sim_time, use_sim_time);
427 ROSCPP_LOG_DEBUG(
"Started node [%s], pid [%d], bound on [%s], xmlrpc port [%d], tcpros port [%d], using [%s] time",
443 char* env_ipv6 = NULL;
445 _dupenv_s(&env_ipv6, NULL,
"ROS_IPV6");
447 env_ipv6 = getenv(
"ROS_IPV6");
450 bool use_ipv6 = (env_ipv6 && strcmp(env_ipv6,
"on") == 0);
462 void init(
const M_string& remappings,
const std::string& name, uint32_t options)
483 signal(SIGPIPE, SIG_IGN);
486 WSAStartup(MAKEWORD(2, 0), &wsaData);
500 void init(
int& argc,
char** argv,
const std::string& name, uint32_t options)
504 int full_argc = argc;
506 for (
int i = 0; i < argc; )
508 std::string arg = argv[i];
509 size_t pos = arg.find(
":=");
510 if (pos != std::string::npos)
512 std::string local_name = arg.substr(0, pos);
513 std::string external_name = arg.substr(pos + 2);
515 ROSCPP_LOG_DEBUG(
"remap: %s => %s", local_name.c_str(), external_name.c_str());
516 remappings[local_name] = external_name;
520 for (
int j = i; j < full_argc - 1; j++)
531 init(remappings, name, options);
534 void init(
const VP_string& remappings,
const std::string& name, uint32_t options)
537 VP_string::const_iterator it = remappings.begin();
538 VP_string::const_iterator end = remappings.end();
539 for (; it != end; ++it)
541 remappings_map[it->first] = it->second;
544 init(remappings_map, name, options);
547 std::string
getROSArg(
int argc,
const char*
const* argv,
const std::string& arg)
549 for (
int i = 0; i < argc; ++i)
551 std::string str_arg = argv[i];
552 size_t pos = str_arg.find(
":=");
553 if (str_arg.substr(0,pos) == arg)
555 return str_arg.substr(pos+2);
563 for (
int i = 0; i < argc; ++i)
565 std::string arg = argv[i];
566 size_t pos = arg.find(
":=");
567 if (pos == std::string::npos)
569 args_out.push_back(arg);
644 static const std::string uri =
"http://localhost:11311";
@ NoRosout
Don't broadcast rosconsole output to the /rosout topic.
void init(const M_string &remappings)
static uint32_t g_init_options
static volatile bool g_shutting_down
void check_ipv6_environment()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROS initialization function.
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.
static bool g_shutdown_registered
static boost::thread g_internal_queue_thread
ROSOutAppender * g_rosout_appender
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
Assign value from parameter server, with default.
void init(const M_string &remappings)
ROSCPP_DECL XmlRpc::XmlRpcValue responseInt(int code, const std::string &msg, int response)
Abstract interface for classes which spin on a callback queue.
void init(const M_string &remappings)
void basicSigintHandler(int sig)
ROSCPP_DECL void spinOnce()
Process a single round of callbacks.
static bool s_use_keepalive_
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
static void setNow(const Time &new_now)
static const ServiceManagerPtr & instance()
std::vector< std::pair< std::string, std::string > > VP_string
CallbackQueuePtr g_global_queue
ROSCPP_DECL void requestShutdown()
Request that the node shut itself down from within a ROS thread.
ROSCPP_DECL bool ok()
Check whether it's time to exit.
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
Resolve a graph resource name into a fully qualified graph resource name.
#define ROSCONSOLE_AUTOINIT
const ROSCPP_DECL std::string & getHost()
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>&...
ROSCONSOLE_DECL void register_appender(LogAppender *appender)
void init(const std::string &names, const M_string &remappings, uint32_t options)
ROSCONSOLE_DECL void shutdown()
static bool useSystemTime()
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
static boost::recursive_mutex g_shutting_down_mutex
Spinner which runs in a single thread.
ROSCPP_DECL bool isInitialized()
Returns whether or not ros::init() has been called.
bool closeAllConnections(roscpp::Empty::Request &, roscpp::Empty::Response &)
bool setLoggerLevel(roscpp::SetLoggerLevel::Request &req, roscpp::SetLoggerLevel::Response &)
bool getLoggers(roscpp::GetLoggers::Request &, roscpp::GetLoggers::Response &resp)
static const XMLRPCManagerPtr & instance()
Encapsulates all options available for creating a ServiceServer.
static CallbackQueuePtr g_internal_callback_queue
static const PollManagerPtr & instance()
void shutdownCallback(XmlRpc::XmlRpcValue ¶ms, XmlRpc::XmlRpcValue &result)
ROSCPP_DECL bool isStarted()
Returns whether or not the node has been started through ros::start()
static boost::mutex g_start_mutex
const Type & getType() const
const ROSCPP_DECL std::string & getName()
Returns the name of the current node.
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
static bool g_shutdown_requested
Encapsulates all options available for creating a Subscriber.
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
This is the default implementation of the ros::CallbackQueueInterface.
bool get_environment_variable(std::string &str, const char *environment_variable)
void clockCallback(const rosgraph_msgs::Clock::ConstPtr &msg)
void enable()
Enable the queue (queue is enabled by default)
static const TopicManagerPtr & instance()
void internalCallbackQueueThreadFunc()
static bool g_atexit_registered
ROSCPP_DECL void waitForShutdown()
Wait for this node to be shutdown, whether through Ctrl-C, ros::shutdown(), or similar.
static const ConnectionManagerPtr & instance()
ROSCPP_DECL bool isShuttingDown()
Returns whether or not ros::shutdown() has been (or is being) called.
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...
CallbackQueuePtr getInternalCallbackQueue()
void init(const M_string &remappings)
@ NoSimTime
Don't consider /use_sim_time parameter and always use system time. Don't create the /clock subscriber...
ROSCPP_DECL void spin()
Enter simple event loop.
std::vector< std::string > V_string
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...
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....
ROSCPP_DECL void initInternalTimerManager()
#define ROSCPP_LOG_DEBUG(...)
static bool g_initialized
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
Returns a pointer to the global default callback queue.
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 Sat Sep 14 2024 02:59:35