Robowflex  v0.1
Making MoveIt Easy
robowflex::ROS Class Reference

RAII-pattern for starting up ROS. More...

#include <util.h>

Public Member Functions

 ROS (int argc, char **argv, const std::string &name="robowflex", unsigned int threads=1)
 Constructor. Start-up ROS. If Boost version is greater than 1.64, rosmaster is started if it is not already running. A signal handler or SIGINT and SIGSEGV is installed to gracefully exit. More...
 
 ~ROS ()
 Destructor. Shutdown ROS. More...
 
std::vector< std::stringgetArgs () const
 Get command-line arguments without ROS parameters. More...
 
void wait () const
 Waits for the process to be killed via some means (normally Ctrl-C) More...
 

Private Attributes

int argc_
 Argument count. More...
 
char ** argv_
 Arguments. More...
 

Detailed Description

RAII-pattern for starting up ROS.

Definition at line 51 of file util.h.

Constructor & Destructor Documentation

◆ ROS()

ROS::ROS ( int  argc,
char **  argv,
const std::string name = "robowflex",
unsigned int  threads = 1 
)

Constructor. Start-up ROS. If Boost version is greater than 1.64, rosmaster is started if it is not already running. A signal handler or SIGINT and SIGSEGV is installed to gracefully exit.

Parameters
[in]argcArgument count forwarded to ros::init
[in]argvArguments forwarded to ros::init
[in]nameName of ROS node.
[in]threadsThreads to use for ROS spinning. If 0 no spinner is created.

Definition at line 68 of file util.cpp.

68  : argc_(argc), argv_(argv)
69 {
70  ros::init(argc, argv, name, ros::init_options::NoSigintHandler);
71  startup();
72 
73  signal(SIGINT, shutdown);
74  signal(SIGSEGV, shutdown);
75 
76  if (threads)
77  {
78  SPINNER.reset(new ros::AsyncSpinner(threads));
79  SPINNER->start();
80  }
81 }
char ** argv_
Arguments.
Definition: util.h:79
int argc_
Argument count.
Definition: util.h:78
T signal(T... args)

◆ ~ROS()

ROS::~ROS ( )

Destructor. Shutdown ROS.

Definition at line 83 of file util.cpp.

84 {
85  shutdown(0);
86 }

Member Function Documentation

◆ getArgs()

std::vector< std::string > ROS::getArgs ( ) const

Get command-line arguments without ROS parameters.

Returns
Vector of command line arguments as strings.

Definition at line 88 of file util.cpp.

89 {
91  ros::removeROSArgs(argc_, argv_, args);
92 
93  return args;
94 }

◆ wait()

void ROS::wait ( ) const

Waits for the process to be killed via some means (normally Ctrl-C)

Definition at line 96 of file util.cpp.

97 {
98  ros::waitForShutdown();
99 }

Member Data Documentation

◆ argc_

int robowflex::ROS::argc_
private

Argument count.

Definition at line 78 of file util.h.

◆ argv_

char** robowflex::ROS::argv_
private

Arguments.

Definition at line 79 of file util.h.


The documentation for this class was generated from the following files: