Go to the documentation of this file.
45 namespace init_options
88 ROSCPP_DECL
void init(
int &argc,
char **argv,
const std::string& name, uint32_t options = 0);
98 ROSCPP_DECL
void init(
const M_string& remappings,
const std::string& name, uint32_t options = 0);
108 ROSCPP_DECL
void init(
const VP_string& remapping_args,
const std::string& name, uint32_t options = 0);
129 ROSCPP_DECL
void spin();
165 ROSCPP_DECL
bool ok();
189 ROSCPP_DECL
void start();
211 ROSCPP_DECL std::string
getROSArg(
int argc,
const char*
const* argv,
const std::string& arg);
@ AnonymousName
Anonymize the node name. Adds a random number to the end of your node's name, to make it unique.
@ NoRosout
Don't broadcast rosconsole output to the /rosout topic.
InitOption
Flags for ROS initialization.
init_options::InitOption InitOption
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROS initialization function.
Abstract interface for classes which spin on a callback queue.
ROSCPP_DECL void spinOnce()
Process a single round of callbacks.
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
std::vector< std::pair< std::string, std::string > > VP_string
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 bool isInitialized()
Returns whether or not ros::init() has been called.
ROSCPP_DECL bool isStarted()
Returns whether or not the node has been started through ros::start()
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
This is the default implementation of the ros::CallbackQueueInterface.
ROSCPP_DECL void waitForShutdown()
Wait for this node to be shutdown, whether through Ctrl-C, ros::shutdown(), or similar.
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...
@ 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 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