RViz plugin for registration metric training. More...
#include <MetricTrainingPanel.h>
Public Member Functions | |
virtual void | load (const rviz::Config &config) |
Load RViz configuration settings. | |
MetricTrainingPanel (QWidget *parent=NULL) | |
Create a new MetricTrainingPanel. | |
virtual void | save (rviz::Config config) const |
Save RViz configuration settings. | |
virtual | ~MetricTrainingPanel () |
Cleans up a MetricTrainingPanel. | |
Private Slots | |
void | executeTrainMetrics () |
Callback for the segment button. | |
void | refresh () |
Refresh with the latest object list. | |
void | setNoFeedback () |
Sets the value of the yes flag to false. | |
void | setYesFeedback () |
Sets the value of the yes flag to true. | |
Private Member Functions | |
void | doneCallback (const actionlib::SimpleClientGoalState &state, const rail_pick_and_place_msgs::TrainMetricsResultConstPtr &result) |
Callback for when the train metrics action server finishes. | |
void | feedbackCallback (const rail_pick_and_place_msgs::TrainMetricsFeedbackConstPtr &feedback) |
Callback for when the train metrics action sends feedback. | |
void | getYesNoFeedbackCallback (const rail_pick_and_place_msgs::GetYesNoFeedbackGoalConstPtr &goal) |
Get the yes/no response from the user. | |
Private Attributes | |
actionlib::SimpleActionServer < rail_pick_and_place_msgs::GetYesNoFeedbackAction > | as_ |
ros::ServiceServer | get_yes_no_feedback_srv_ |
graspdb::Client * | graspdb_ |
boost::mutex | mutex_ |
QPushButton * | no_button_ |
ros::NodeHandle | node_ |
QComboBox * | object_list_ |
QPushButton * | refresh_button_ |
bool | responded_ |
actionlib::SimpleActionClient < rail_pick_and_place_msgs::TrainMetricsAction > | train_metrics_ac_ |
QPushButton * | train_metrics_button_ |
QLabel * | train_metrics_status_ |
bool | yes_ |
QPushButton * | yes_button_ |
RViz plugin for registration metric training.
The metric training panel allows for sending metric training requests and getting user Yes/No feedback.
Definition at line 42 of file MetricTrainingPanel.h.
MetricTrainingPanel::MetricTrainingPanel | ( | QWidget * | parent = NULL | ) |
Create a new MetricTrainingPanel.
Creates a new MetricTrainingPanel and adds the correct widgets.
parent | The parent widget for this panel (defaults to NULL). |
Definition at line 23 of file MetricTrainingPanel.cpp.
MetricTrainingPanel::~MetricTrainingPanel | ( | ) | [virtual] |
Cleans up a MetricTrainingPanel.
Cleans up any connections used by the MetricTrainingPanel.
Definition at line 110 of file MetricTrainingPanel.cpp.
void MetricTrainingPanel::doneCallback | ( | const actionlib::SimpleClientGoalState & | state, |
const rail_pick_and_place_msgs::TrainMetricsResultConstPtr & | result | ||
) | [private] |
Callback for when the train metrics action server finishes.
Sets the status message to the corresponding message.
state | The finished goal state. |
result | The result of the action client call. |
Definition at line 211 of file MetricTrainingPanel.cpp.
void MetricTrainingPanel::executeTrainMetrics | ( | ) | [private, slot] |
Callback for the segment button.
Calls the segmentation service.
Definition at line 189 of file MetricTrainingPanel.cpp.
void MetricTrainingPanel::feedbackCallback | ( | const rail_pick_and_place_msgs::TrainMetricsFeedbackConstPtr & | feedback | ) | [private] |
Callback for when the train metrics action sends feedback.
Sets the status message to the corresponding message.
feedback | The current feedback message. |
Definition at line 229 of file MetricTrainingPanel.cpp.
void MetricTrainingPanel::getYesNoFeedbackCallback | ( | const rail_pick_and_place_msgs::GetYesNoFeedbackGoalConstPtr & | goal | ) | [private] |
Get the yes/no response from the user.
Enables the yes/no buttons and waits for the user's response.
goal | The empty goal. |
Definition at line 118 of file MetricTrainingPanel.cpp.
void MetricTrainingPanel::load | ( | const rviz::Config & | config | ) | [virtual] |
Load RViz configuration settings.
No settings are saved or loaded for this panel.
config | The RViz configuration settings to load. |
Reimplemented from rviz::Panel.
Definition at line 241 of file MetricTrainingPanel.cpp.
void MetricTrainingPanel::refresh | ( | ) | [private, slot] |
Refresh with the latest object list.
Refreshes the interface with the latest object list.
Definition at line 167 of file MetricTrainingPanel.cpp.
void MetricTrainingPanel::save | ( | rviz::Config | config | ) | const [virtual] |
Save RViz configuration settings.
No settings are saved or loaded for this panel.
config | The RViz configuration settings to save. |
Reimplemented from rviz::Panel.
Definition at line 235 of file MetricTrainingPanel.cpp.
void MetricTrainingPanel::setNoFeedback | ( | ) | [private, slot] |
Sets the value of the yes flag to false.
Indicates the user selected "no".
Definition at line 159 of file MetricTrainingPanel.cpp.
void MetricTrainingPanel::setYesFeedback | ( | ) | [private, slot] |
Sets the value of the yes flag to true.
Indicates the user selected "yes".
Definition at line 151 of file MetricTrainingPanel.cpp.
actionlib::SimpleActionServer<rail_pick_and_place_msgs::GetYesNoFeedbackAction> rail::pick_and_place::MetricTrainingPanel::as_ [private] |
The user feedback action server.
Definition at line 126 of file MetricTrainingPanel.h.
The main user response service.
Definition at line 124 of file MetricTrainingPanel.h.
The grasp database connection.
Definition at line 114 of file MetricTrainingPanel.h.
boost::mutex rail::pick_and_place::MetricTrainingPanel::mutex_ [private] |
Mutex for locking on the response flag.
Definition at line 119 of file MetricTrainingPanel.h.
QPushButton * rail::pick_and_place::MetricTrainingPanel::no_button_ [private] |
Definition at line 133 of file MetricTrainingPanel.h.
The ROS node handle.
Definition at line 122 of file MetricTrainingPanel.h.
QComboBox* rail::pick_and_place::MetricTrainingPanel::object_list_ [private] |
The current list of objects
Definition at line 131 of file MetricTrainingPanel.h.
QPushButton * rail::pick_and_place::MetricTrainingPanel::refresh_button_ [private] |
Definition at line 133 of file MetricTrainingPanel.h.
bool rail::pick_and_place::MetricTrainingPanel::responded_ [private] |
If the user has responded yet and their response.
Definition at line 116 of file MetricTrainingPanel.h.
actionlib::SimpleActionClient<rail_pick_and_place_msgs::TrainMetricsAction> rail::pick_and_place::MetricTrainingPanel::train_metrics_ac_ [private] |
The train metrics action client.
Definition at line 128 of file MetricTrainingPanel.h.
QPushButton* rail::pick_and_place::MetricTrainingPanel::train_metrics_button_ [private] |
The train metrics, refresh, and feedback buttons.
Definition at line 133 of file MetricTrainingPanel.h.
QLabel* rail::pick_and_place::MetricTrainingPanel::train_metrics_status_ [private] |
The train metrics status text.
Definition at line 135 of file MetricTrainingPanel.h.
bool rail::pick_and_place::MetricTrainingPanel::yes_ [private] |
Definition at line 116 of file MetricTrainingPanel.h.
QPushButton * rail::pick_and_place::MetricTrainingPanel::yes_button_ [private] |
Definition at line 133 of file MetricTrainingPanel.h.