#include <qnode.hpp>
Public Types | |
| enum | LogLevel { Debug, Info, Warn, Error, Fatal } |
Public Slots | |
| void | cont () |
| void | stop () |
Signals | |
| void | loggingUpdated () |
| void | rosShutdown () |
Public Member Functions | |
| void | goalpub (const geometry_msgs::PoseStamped::ConstPtr msg) |
| bool | init () |
| bool | init (const std::string &master_url, const std::string &host_url) |
| void | log (const LogLevel &level, const std::string &msg) |
| QStringListModel * | loggingModel () |
| QNode (int argc, char **argv) | |
| void | run () |
| void | stopmsg (const geometry_msgs::PoseStamped::ConstPtr msg) |
| virtual | ~QNode () |
Public Attributes | |
| boost::shared_ptr < actionlib::SimpleActionClient < move_base_msgs::MoveBaseAction > > | client |
| int | init_argc |
| char ** | init_argv |
| QStringListModel | logging_model |
| boost::shared_ptr < move_base_msgs::MoveBaseGoal > | mostRecentGoal |
| boost::shared_ptr < ros::Subscriber > | sub |
| segbot_controller::QNode::QNode | ( | int | argc, |
| char ** | argv | ||
| ) |
| segbot_controller::QNode::~QNode | ( | ) | [virtual] |
| void segbot_controller::QNode::cont | ( | ) | [slot] |
| void segbot_controller::QNode::goalpub | ( | const geometry_msgs::PoseStamped::ConstPtr | msg | ) |
| bool segbot_controller::QNode::init | ( | ) |
| bool segbot_controller::QNode::init | ( | const std::string & | master_url, |
| const std::string & | host_url | ||
| ) |
| void segbot_controller::QNode::log | ( | const LogLevel & | level, |
| const std::string & | msg | ||
| ) |
| QStringListModel* segbot_controller::QNode::loggingModel | ( | ) | [inline] |
| void segbot_controller::QNode::loggingUpdated | ( | ) | [signal] |
| void segbot_controller::QNode::rosShutdown | ( | ) | [signal] |
| void segbot_controller::QNode::run | ( | ) |
| void segbot_controller::QNode::stop | ( | ) | [slot] |
| void segbot_controller::QNode::stopmsg | ( | const geometry_msgs::PoseStamped::ConstPtr | msg | ) |
| boost::shared_ptr<actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> > segbot_controller::QNode::client |
| QStringListModel segbot_controller::QNode::logging_model |
| boost::shared_ptr<move_base_msgs::MoveBaseGoal> segbot_controller::QNode::mostRecentGoal |
| boost::shared_ptr<ros::Subscriber> segbot_controller::QNode::sub |