#include <QtRosNode.h>
Public Types | |
enum | ModuleStateT { IDLE, WAITING, DOOR_IS_OPEN } |
Public Slots | |
void | quitNow () |
Connect to aboutToQuit signals, to stop the thread. | |
Signals | |
void | learningStatus (std::vector< std::string > filenames, std::string objType) |
void | mapUpdated (unsigned char *pMap, unsigned size, double resolution, geometry_msgs::Pose origin, int minX, int minY, int maxX, int maxY) |
void | objectNames (std::vector< std::string > names, std::vector< std::string > types) |
void | pathUpdated (std::vector< geometry_msgs::PoseStamped > path) |
void | poiListUpdated (std::vector< map_messages::PointOfInterest > poiList) |
void | poseUpdated (double x, double y, double theta) |
void | rosShutdown () |
Triggered if ros::ok() != true. | |
Public Member Functions | |
ros::NodeHandle * | getNodeHandle () |
QtRosNode (int argc, char *argv[], const char *node_name, MainWindow *mainWindow) | |
void | run () |
This method contains the ROS event loop. Feel free to modify. | |
~QtRosNode () | |
Private Member Functions | |
void | advertiseTopics () |
void | callbackLaserScan (const sensor_msgs::LaserScan::ConstPtr &msg) |
void | callbackLearningStatus (const or_msgs::OrLearningStatusConstPtr &msg) |
void | callbackObjectNames (const or_msgs::OrObjectNamesConstPtr &msg) |
void | callbackOccupancyGrid (const nav_msgs::OccupancyGrid::ConstPtr &msg) |
void | callbackPOIList (const map_messages::PointsOfInterest::ConstPtr &msg) |
void | callbackPoseStamped (const geometry_msgs::PoseStamped::ConstPtr &msg) |
void | compareRanges () |
void | subscribeToTopics () |
Private Attributes | |
QApplication * | m_Application |
int | m_CurrentRange |
unsigned int | m_CurrentTimestamp |
std::string | m_ExtraStatusInfo |
int | m_GameTime |
int | m_InitRange |
unsigned int | m_InitTimestamp |
ros::Subscriber | m_LaserSubscriber |
MainWindow * | m_MainWindow |
ros::Subscriber | m_MapDataSubscriber |
StateMachine< ModuleStateT > | m_ModuleMachine |
int | m_NewRange |
unsigned int | m_NewTimestamp |
ros::NodeHandle * | m_NodeHandle |
ros::Subscriber | m_OLPrimaryImageSubscriber |
ros::Subscriber | m_ORLearningStatusSubscriber |
ros::Subscriber | m_ORObjectNamesSubscriber |
ros::Subscriber | m_PathSubscriber |
ros::Subscriber | m_POIsSubscriber |
ros::Subscriber | m_PoseStampedSubscriber |
std::vector< int > | m_Ranges |
ros::Subscriber | m_RgbImageSubscriber |
ros::Subscriber | m_TextSubscriber |
bool | quitfromgui |
Definition at line 28 of file QtRosNode.h.
Definition at line 45 of file QtRosNode.h.
QtRosNode::QtRosNode | ( | int | argc, |
char * | argv[], | ||
const char * | node_name, | ||
MainWindow * | mainWindow | ||
) |
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 15 of file QtRosNode.cpp.
Definition at line 42 of file QtRosNode.cpp.
void QtRosNode::advertiseTopics | ( | ) | [private] |
Definition at line 103 of file QtRosNode.cpp.
void QtRosNode::callbackLaserScan | ( | const sensor_msgs::LaserScan::ConstPtr & | msg | ) | [private] |
Definition at line 195 of file QtRosNode.cpp.
void QtRosNode::callbackLearningStatus | ( | const or_msgs::OrLearningStatusConstPtr & | msg | ) | [private] |
Definition at line 248 of file QtRosNode.cpp.
void QtRosNode::callbackObjectNames | ( | const or_msgs::OrObjectNamesConstPtr & | msg | ) | [private] |
Definition at line 253 of file QtRosNode.cpp.
void QtRosNode::callbackOccupancyGrid | ( | const nav_msgs::OccupancyGrid::ConstPtr & | msg | ) | [private] |
Definition at line 144 of file QtRosNode.cpp.
void QtRosNode::callbackPOIList | ( | const map_messages::PointsOfInterest::ConstPtr & | msg | ) | [private] |
Definition at line 177 of file QtRosNode.cpp.
void QtRosNode::callbackPoseStamped | ( | const geometry_msgs::PoseStamped::ConstPtr & | msg | ) | [private] |
Definition at line 138 of file QtRosNode.cpp.
void QtRosNode::compareRanges | ( | ) | [private] |
Definition at line 53 of file QtRosNode.cpp.
ros::NodeHandle* QtRosNode::getNodeHandle | ( | ) | [inline] |
Definition at line 40 of file QtRosNode.h.
void QtRosNode::learningStatus | ( | std::vector< std::string > | filenames, |
std::string | objType | ||
) | [signal] |
void QtRosNode::mapUpdated | ( | unsigned char * | pMap, |
unsigned | size, | ||
double | resolution, | ||
geometry_msgs::Pose | origin, | ||
int | minX, | ||
int | minY, | ||
int | maxX, | ||
int | maxY | ||
) | [signal] |
void QtRosNode::objectNames | ( | std::vector< std::string > | names, |
std::vector< std::string > | types | ||
) | [signal] |
void QtRosNode::pathUpdated | ( | std::vector< geometry_msgs::PoseStamped > | path | ) | [signal] |
void QtRosNode::poiListUpdated | ( | std::vector< map_messages::PointOfInterest > | poiList | ) | [signal] |
void QtRosNode::poseUpdated | ( | double | x, |
double | y, | ||
double | theta | ||
) | [signal] |
void QtRosNode::quitNow | ( | ) | [slot] |
Connect to aboutToQuit signals, to stop the thread.
Definition at line 119 of file QtRosNode.cpp.
void QtRosNode::rosShutdown | ( | ) | [signal] |
Triggered if ros::ok() != true.
void QtRosNode::run | ( | ) |
This method contains the ROS event loop. Feel free to modify.
Definition at line 125 of file QtRosNode.cpp.
void QtRosNode::subscribeToTopics | ( | ) | [private] |
Definition at line 87 of file QtRosNode.cpp.
QApplication* QtRosNode::m_Application [private] |
Definition at line 74 of file QtRosNode.h.
int QtRosNode::m_CurrentRange [private] |
Definition at line 112 of file QtRosNode.h.
unsigned int QtRosNode::m_CurrentTimestamp [private] |
Definition at line 109 of file QtRosNode.h.
std::string QtRosNode::m_ExtraStatusInfo [private] |
Definition at line 106 of file QtRosNode.h.
int QtRosNode::m_GameTime [private] |
Definition at line 114 of file QtRosNode.h.
int QtRosNode::m_InitRange [private] |
Definition at line 111 of file QtRosNode.h.
unsigned int QtRosNode::m_InitTimestamp [private] |
Definition at line 108 of file QtRosNode.h.
ros::Subscriber QtRosNode::m_LaserSubscriber [private] |
Definition at line 77 of file QtRosNode.h.
MainWindow* QtRosNode::m_MainWindow [private] |
Definition at line 73 of file QtRosNode.h.
Definition at line 81 of file QtRosNode.h.
StateMachine<ModuleStateT> QtRosNode::m_ModuleMachine [private] |
Definition at line 103 of file QtRosNode.h.
int QtRosNode::m_NewRange [private] |
Definition at line 113 of file QtRosNode.h.
unsigned int QtRosNode::m_NewTimestamp [private] |
Definition at line 110 of file QtRosNode.h.
ros::NodeHandle* QtRosNode::m_NodeHandle [private] |
Definition at line 72 of file QtRosNode.h.
Definition at line 85 of file QtRosNode.h.
Definition at line 86 of file QtRosNode.h.
Definition at line 87 of file QtRosNode.h.
ros::Subscriber QtRosNode::m_PathSubscriber [private] |
Definition at line 83 of file QtRosNode.h.
ros::Subscriber QtRosNode::m_POIsSubscriber [private] |
Definition at line 82 of file QtRosNode.h.
Definition at line 80 of file QtRosNode.h.
std::vector<int> QtRosNode::m_Ranges [private] |
Definition at line 107 of file QtRosNode.h.
Definition at line 78 of file QtRosNode.h.
ros::Subscriber QtRosNode::m_TextSubscriber [private] |
Definition at line 76 of file QtRosNode.h.
bool QtRosNode::quitfromgui [private] |
Definition at line 70 of file QtRosNode.h.