Public Slots | Signals | Public Member Functions | Private Attributes
QtROS Class Reference

Sets up a thread for ROS event processing. More...

#include <qtros.h>

List of all members.

Public Slots

void quitNow ()
 Connect to aboutToQuit signals, to stop the thread.

Signals

void rosQuits ()
 Triggered if ros::ok() != true.

Public Member Functions

ros::NodeHandle getNodeHandle ()
 QtROS (int argc, char *argv[], const char *node_name)
void run ()
 This method contains the ROS event loop. Feel free to modify.

Private Attributes

ros::NodeHandlen
bool quitfromgui

Detailed Description

Sets up a thread for ROS event processing.

QtThread based class encapsulating the ros basics, i.e., init, node handle creation, spining and quitting. To quit via qt, connect the quitNow slot to, e.g., the aboutToQuit-Signal of qapplication.

Definition at line 31 of file qtros.h.


Constructor & Destructor Documentation

QtROS::QtROS ( int  argc,
char *  argv[],
const char *  node_name 
)

Note: The constructor will block until connected with roscore Instead of ros::spin(), start this thread with the start() method to run the event loop of ros

Definition at line 20 of file qtros.cpp.


Member Function Documentation

Definition at line 39 of file qtros.h.

void QtROS::quitNow ( ) [slot]

Connect to aboutToQuit signals, to stop the thread.

Definition at line 28 of file qtros.cpp.

void QtROS::rosQuits ( ) [signal]

Triggered if ros::ok() != true.

void QtROS::run ( void  )

This method contains the ROS event loop. Feel free to modify.

Definition at line 32 of file qtros.cpp.


Member Data Documentation

Definition at line 50 of file qtros.h.

Definition at line 49 of file qtros.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


rgbdslam
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Wed Dec 26 2012 15:53:09