init.h
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 #ifndef ROSCPP_INIT_H
36 #define ROSCPP_INIT_H
37 
38 #include "ros/forwards.h"
39 #include "ros/spinner.h"
40 #include "common.h"
41 
42 namespace ros
43 {
44 
45 namespace init_options
46 {
51 {
56  NoSigintHandler = 1 << 0,
59  AnonymousName = 1 << 1,
63  NoRosout = 1 << 2,
68  NoSimTime = 1 << 3,
69 };
70 }
72 
88 ROSCPP_DECL void init(int &argc, char **argv, const std::string& name, uint32_t options = 0);
89 
98 ROSCPP_DECL void init(const M_string& remappings, const std::string& name, uint32_t options = 0);
99 
108 ROSCPP_DECL void init(const VP_string& remapping_args, const std::string& name, uint32_t options = 0);
109 
113 ROSCPP_DECL bool isInitialized();
117 ROSCPP_DECL bool isShuttingDown();
118 
129 ROSCPP_DECL void spin();
130 
143 ROSCPP_DECL void spin(Spinner& spinner);
152 ROSCPP_DECL void spinOnce();
153 
157 ROSCPP_DECL void waitForShutdown();
158 
165 ROSCPP_DECL bool ok();
172 ROSCPP_DECL void shutdown();
173 
179 ROSCPP_DECL void requestShutdown();
180 
189 ROSCPP_DECL void start();
193 ROSCPP_DECL bool isStarted();
194 
202 
211 ROSCPP_DECL std::string getROSArg(int argc, const char* const* argv, const std::string& arg);
212 
221 ROSCPP_DECL void removeROSArgs(int argc, const char* const* argv, V_string& args_out);
222 
226 ROSCPP_DECL const std::string& getDefaultMasterURI();
227 
228 }
229 
230 #endif
ros::init_options::AnonymousName
@ AnonymousName
Anonymize the node name. Adds a random number to the end of your node's name, to make it unique.
Definition: init.h:59
ros::init_options::NoRosout
@ NoRosout
Don't broadcast rosconsole output to the /rosout topic.
Definition: init.h:63
ros::init_options::InitOption
InitOption
Flags for ROS initialization.
Definition: init.h:50
ros::InitOption
init_options::InitOption InitOption
Definition: init.h:71
ros::init
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROS initialization function.
Definition: init.cpp:500
forwards.h
ros
ros::Spinner
Abstract interface for classes which spin on a callback queue.
Definition: spinner.h:44
spinner.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
Process a single round of callbacks.
Definition: init.cpp:585
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:608
ros::VP_string
std::vector< std::pair< std::string, std::string > > VP_string
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:603
ros::isInitialized
ROSCPP_DECL bool isInitialized()
Returns whether or not ros::init() has been called.
Definition: init.cpp:111
ros::isStarted
ROSCPP_DECL bool isStarted()
Returns whether or not the node has been started through ros::start()
Definition: init.cpp:289
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::CallbackQueue
This is the default implementation of the ros::CallbackQueueInterface.
Definition: callback_queue.h:57
ros::waitForShutdown
ROSCPP_DECL void waitForShutdown()
Wait for this node to be shutdown, whether through Ctrl-C, ros::shutdown(), or similar.
Definition: init.cpp:590
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:547
ros::init_options::NoSimTime
@ NoSimTime
Don't consider /use_sim_time parameter and always use system time. Don't create the /clock subscriber...
Definition: init.h:68
ros::spin
ROSCPP_DECL void spin()
Enter simple event loop.
Definition: init.cpp:574
ros::V_string
std::vector< std::string > V_string
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:643
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:561
ros::init_options::NoSigintHandler
@ NoSigintHandler
Definition: init.h:56
ros::getGlobalCallbackQueue
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
Returns a pointer to the global default callback queue.
Definition: init.cpp:598
ros::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 Sat Sep 14 2024 02:59:35