Public Member Functions | Protected Slots | Protected Member Functions | Protected Attributes | List of all members
choreo_gui::ChoreoWidget Class Reference

The ChoreoWidget class works in states: More...

#include <choreo_widget.h>

Inheritance diagram for choreo_gui::ChoreoWidget:
Inheritance graph
[legend]

Public Member Functions

void appendText (const std::string &txt)
 
 ChoreoWidget (QWidget *parent=0)
 
ros::NodeHandlenodeHandle ()
 
ParamsSubmenuparams ()
 
SelectionWidgetselection_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

GuiStateactive_state_
 
ros::ServiceClient choreo_parameters_client_
 
ros::NodeHandle nh_
 
ParamsSubmenuparams_
 
SelectionWidgetselection_widget_
 
actionlib::SimpleActionClient< choreo_msgs::SimulateMotionPlanAction > simulate_motion_plan_action_client_
 
Ui::ChoreoWidget * ui_
 

Detailed Description

The ChoreoWidget class works in states:

  1. System Init State
  2. Task Sequence Planning State (require computed path info from choreo) 2' Task Sequence Processing State
  3. Select Path State (user select path for process planning)
  4. Process Planning State (motion planning and fill in trajectory library)
  5. Select Plan State (User selects plans, simulate and output)

Definition at line 34 of file choreo_widget.h.

Constructor & Destructor Documentation

choreo_gui::ChoreoWidget::ChoreoWidget ( QWidget *  parent = 0)

Definition at line 18 of file choreo_widget.cpp.

choreo_gui::ChoreoWidget::~ChoreoWidget ( )
virtual

Definition at line 65 of file choreo_widget.cpp.

Member Function Documentation

void choreo_gui::ChoreoWidget::appendText ( const std::string &  txt)

Definition at line 76 of file choreo_widget.cpp.

void choreo_gui::ChoreoWidget::changeState ( GuiState new_state)
protectedslot

Definition at line 170 of file choreo_widget.cpp.

void choreo_gui::ChoreoWidget::loadParameters ( )
protected

Definition at line 205 of file choreo_widget.cpp.

ros::NodeHandle& choreo_gui::ChoreoWidget::nodeHandle ( )
inline

Definition at line 53 of file choreo_widget.h.

void choreo_gui::ChoreoWidget::onBackButton ( )
protectedslot

Definition at line 88 of file choreo_widget.cpp.

void choreo_gui::ChoreoWidget::onDisableButtons ( )
protectedslot

Definition at line 142 of file choreo_widget.cpp.

void choreo_gui::ChoreoWidget::onEnableButtons ( )
protectedslot

Definition at line 137 of file choreo_widget.cpp.

void choreo_gui::ChoreoWidget::onNextButton ( )
protectedslot

Definition at line 83 of file choreo_widget.cpp.

void choreo_gui::ChoreoWidget::onParamsAccept ( )
protectedslot

Definition at line 124 of file choreo_widget.cpp.

void choreo_gui::ChoreoWidget::onParamsButton ( )
protectedslot

Definition at line 105 of file choreo_widget.cpp.

void choreo_gui::ChoreoWidget::onParamsSave ( )
protectedslot

Definition at line 111 of file choreo_widget.cpp.

void choreo_gui::ChoreoWidget::onPicknPlace ( )
protectedslot

Definition at line 147 of file choreo_widget.cpp.

void choreo_gui::ChoreoWidget::onResetButton ( )
protectedslot

Definition at line 93 of file choreo_widget.cpp.

void choreo_gui::ChoreoWidget::onUseSavedResult ( bool  )
protectedslot
ParamsSubmenu& choreo_gui::ChoreoWidget::params ( )
inline

Definition at line 54 of file choreo_widget.h.

SelectionWidget& choreo_gui::ChoreoWidget::selection_widget ( )
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.

void choreo_gui::ChoreoWidget::showOutputSaveDirParams ( )
protectedslot

Definition at line 188 of file choreo_widget.cpp.

Member Data Documentation

GuiState* choreo_gui::ChoreoWidget::active_state_
protected

Definition at line 93 of file choreo_widget.h.

ros::ServiceClient choreo_gui::ChoreoWidget::choreo_parameters_client_
protected

Definition at line 96 of file choreo_widget.h.

ros::NodeHandle choreo_gui::ChoreoWidget::nh_
protected

Definition at line 90 of file choreo_widget.h.

ParamsSubmenu* choreo_gui::ChoreoWidget::params_
protected

Definition at line 86 of file choreo_widget.h.

SelectionWidget* choreo_gui::ChoreoWidget::selection_widget_
protected

Definition at line 87 of file choreo_widget.h.

actionlib::SimpleActionClient<choreo_msgs::SimulateMotionPlanAction> choreo_gui::ChoreoWidget::simulate_motion_plan_action_client_
protected

Definition at line 98 of file choreo_widget.h.

Ui::ChoreoWidget* choreo_gui::ChoreoWidget::ui_
protected

Definition at line 85 of file choreo_widget.h.


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


choreo_gui
Author(s): Yijiang Huang
autogenerated on Thu Jul 18 2019 03:58:56