The ChoreoWidget class works in states: More...
#include <choreo_widget.h>

Public Member Functions | |
| void | appendText (const std::string &txt) |
| ChoreoWidget (QWidget *parent=0) | |
| ros::NodeHandle & | nodeHandle () |
| ParamsSubmenu & | params () |
| SelectionWidget & | selection_widget () |
| void | sendGoal (const choreo_msgs::SimulateMotionPlanGoal &goal) |
| void | sendGoalAndWait (const choreo_msgs::SimulateMotionPlanGoal &goal) |
| void | setButtonsEnabled (bool enabled) |
| void | setLabelText (const std::string &txt) |
| void | setParamsButtonEnabled (bool enabled) |
| void | setText (const std::string &txt) |
| virtual | ~ChoreoWidget () |
Protected Slots | |
| void | changeState (GuiState *new_state) |
| void | onBackButton () |
| void | onDisableButtons () |
| void | onEnableButtons () |
| void | onNextButton () |
| void | onParamsAccept () |
| void | onParamsButton () |
| void | onParamsSave () |
| void | onPicknPlace () |
| void | onResetButton () |
| void | onUseSavedResult (bool) |
| void | showOutputSaveDirParams () |
Protected Member Functions | |
| void | loadParameters () |
Protected Attributes | |
| GuiState * | active_state_ |
| ros::ServiceClient | choreo_parameters_client_ |
| ros::NodeHandle | nh_ |
| ParamsSubmenu * | params_ |
| SelectionWidget * | selection_widget_ |
| actionlib::SimpleActionClient< choreo_msgs::SimulateMotionPlanAction > | simulate_motion_plan_action_client_ |
| Ui::ChoreoWidget * | ui_ |
The ChoreoWidget class works in states:
Definition at line 34 of file choreo_widget.h.
| choreo_gui::ChoreoWidget::ChoreoWidget | ( | QWidget * | parent = 0 | ) |
Definition at line 18 of file choreo_widget.cpp.
|
virtual |
Definition at line 65 of file choreo_widget.cpp.
| void choreo_gui::ChoreoWidget::appendText | ( | const std::string & | txt | ) |
Definition at line 76 of file choreo_widget.cpp.
|
protectedslot |
Definition at line 170 of file choreo_widget.cpp.
|
protected |
Definition at line 205 of file choreo_widget.cpp.
|
inline |
Definition at line 53 of file choreo_widget.h.
|
protectedslot |
Definition at line 88 of file choreo_widget.cpp.
|
protectedslot |
Definition at line 142 of file choreo_widget.cpp.
|
protectedslot |
Definition at line 137 of file choreo_widget.cpp.
|
protectedslot |
Definition at line 83 of file choreo_widget.cpp.
|
protectedslot |
Definition at line 124 of file choreo_widget.cpp.
|
protectedslot |
Definition at line 105 of file choreo_widget.cpp.
|
protectedslot |
Definition at line 111 of file choreo_widget.cpp.
|
protectedslot |
Definition at line 147 of file choreo_widget.cpp.
|
protectedslot |
Definition at line 93 of file choreo_widget.cpp.
|
protectedslot |
|
inline |
Definition at line 54 of file choreo_widget.h.
|
inline |
Definition at line 55 of file choreo_widget.h.
| void choreo_gui::ChoreoWidget::sendGoal | ( | const choreo_msgs::SimulateMotionPlanGoal & | goal | ) |
Definition at line 241 of file choreo_widget.cpp.
| void choreo_gui::ChoreoWidget::sendGoalAndWait | ( | const choreo_msgs::SimulateMotionPlanGoal & | goal | ) |
Definition at line 246 of file choreo_widget.cpp.
| void choreo_gui::ChoreoWidget::setButtonsEnabled | ( | bool | enabled | ) |
Definition at line 193 of file choreo_widget.cpp.
| void choreo_gui::ChoreoWidget::setLabelText | ( | const std::string & | txt | ) |
Definition at line 236 of file choreo_widget.cpp.
| void choreo_gui::ChoreoWidget::setParamsButtonEnabled | ( | bool | enabled | ) |
Definition at line 200 of file choreo_widget.cpp.
| void choreo_gui::ChoreoWidget::setText | ( | const std::string & | txt | ) |
Definition at line 71 of file choreo_widget.cpp.
|
protectedslot |
Definition at line 188 of file choreo_widget.cpp.
|
protected |
Definition at line 93 of file choreo_widget.h.
|
protected |
Definition at line 96 of file choreo_widget.h.
|
protected |
Definition at line 90 of file choreo_widget.h.
|
protected |
Definition at line 86 of file choreo_widget.h.
|
protected |
Definition at line 87 of file choreo_widget.h.
|
protected |
Definition at line 98 of file choreo_widget.h.
|
protected |
Definition at line 85 of file choreo_widget.h.