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,
64 };
65 }
67 
83 ROSCPP_DECL void init(int &argc, char **argv, const std::string& name, uint32_t options = 0);
84 
93 ROSCPP_DECL void init(const M_string& remappings, const std::string& name, uint32_t options = 0);
94 
103 ROSCPP_DECL void init(const VP_string& remapping_args, const std::string& name, uint32_t options = 0);
104 
108 ROSCPP_DECL bool isInitialized();
112 ROSCPP_DECL bool isShuttingDown();
113 
124 ROSCPP_DECL void spin();
125 
138 ROSCPP_DECL void spin(Spinner& spinner);
147 ROSCPP_DECL void spinOnce();
148 
152 ROSCPP_DECL void waitForShutdown();
153 
160 ROSCPP_DECL bool ok();
167 ROSCPP_DECL void shutdown();
168 
174 ROSCPP_DECL void requestShutdown();
175 
184 ROSCPP_DECL void start();
188 ROSCPP_DECL bool isStarted();
189 
197 
206 ROSCPP_DECL std::string getROSArg(int argc, const char* const* argv, const std::string& arg);
207 
216 ROSCPP_DECL void removeROSArgs(int argc, const char* const* argv, V_string& args_out);
217 
218 }
219 
220 #endif
This is the default implementation of the ros::CallbackQueueInterface.
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
Definition: init.cpp:293
std::vector< std::pair< std::string, std::string > > VP_string
Anonymize the node name. Adds a random number to the end of your node&#39;s name, to make it unique...
Definition: init.h:59
ROSCPP_DECL bool isInitialized()
Returns whether or not ros::init() has been called.
Definition: init.cpp:110
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROS initialization function.
Definition: init.cpp:470
InitOption
Flags for ROS initialization.
Definition: init.h:50
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
Returns a pointer to the global default callback queue.
Definition: init.cpp:568
std::map< std::string, std::string > M_string
Abstract interface for classes which spin on a callback queue.
Definition: spinner.h:44
std::vector< std::string > V_string
ROSCPP_DECL bool ok()
Check whether it&#39;s time to exit.
Definition: init.cpp:573
ROSCPP_DECL bool isShuttingDown()
Returns whether or not ros::shutdown() has been (or is being) called.
Definition: init.cpp:115
ROSCPP_DECL void spin()
Enter simple event loop.
Definition: init.cpp:544
Don&#39;t broadcast rosconsole output to the /rosout topic.
Definition: init.h:63
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:517
ROSCPP_DECL void requestShutdown()
Request that the node shut itself down from within a ROS thread.
Definition: init.cpp:141
ROSCPP_DECL bool isStarted()
Returns whether or not the node has been started through ros::start()
Definition: init.cpp:288
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
Definition: init.cpp:578
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. Useful if you need to parse your arguments to determine your node name
Definition: init.cpp:531
ROSCPP_DECL void spinOnce()
Process a single round of callbacks.
Definition: init.cpp:555
ROSCPP_DECL void waitForShutdown()
Wait for this node to be shutdown, whether through Ctrl-C, ros::shutdown(), or similar.
Definition: init.cpp:560


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Sun Feb 3 2019 03:29:54