#include <main_window.h>
Classes | |
class | StartState |
Public Slots | |
void | benchmarkFolderButtonClicked (void) |
void | cancelBenchmarkButtonClicked (void) |
void | checkGoalsInCollision (void) |
void | checkGoalsReachable (void) |
void | copySelectedGoalPoses (void) |
void | createBBoxGoalsButtonClicked (void) |
void | createGoalAtPose (const std::string &name, const Eigen::Affine3d &pose) |
void | createGoalPoseButtonClicked (void) |
void | createTrajectoryButtonClicked (void) |
void | dbConnectButtonClicked () |
void | dbConnectButtonClickedBackgroundJob () |
void | deleteGoalsOnDBButtonClicked (void) |
void | deleteStatesOnDBButtonClicked (void) |
void | exitActionTriggered (bool) |
void | goalOffsetChanged () |
void | goalPoseDoubleClicked (QListWidgetItem *item) |
void | goalPoseFeedback (visualization_msgs::InteractiveMarkerFeedback &feedback) |
void | goalPoseSelectionChanged (void) |
void | loadBenchmarkResults (void) |
void | loadGoalsFromDBButtonClicked (void) |
void | loadSceneButtonClicked (void) |
void | loadSceneButtonClicked (QListWidgetItem *item) |
void | loadStatesFromDBButtonClicked (void) |
void | loadTrajectoriesFromDBButtonClicked (void) |
void | MainLoop () |
void | openActionTriggered (bool) |
void | planningGroupChanged (const QString &text) |
void | removeAllGoalsButtonClicked (void) |
void | removeAllStatesButtonClicked (void) |
void | removeSelectedGoalsButtonClicked (void) |
void | removeSelectedStatesButtonClicked (void) |
void | removeTrajectoryButtonClicked (void) |
void | robotInteractionButtonClicked () |
void | runBenchmark (void) |
void | runBenchmarkButtonClicked (void) |
bool | saveBenchmarkConfigButtonClicked (void) |
void | saveGoalsOnDBButtonClicked (void) |
void | saveStartStateButtonClicked (void) |
void | saveStatesOnDBButtonClicked (void) |
void | saveTrajectoriesOnDBButtonClicked (void) |
void | showBBoxGoalsDialog () |
void | startStateItemDoubleClicked (QListWidgetItem *item) |
void | switchGoalVisibilityButtonClicked (void) |
void | trajectoryExecuteButtonClicked (void) |
void | trajectoryNWaypointsChanged (int) |
void | trajectorySelectionChanged (void) |
void | updateGoalMarkerStateFromName (const std::string &name, const GripperMarker::GripperMarkerState &state) |
void | updateMarkerState (GripperMarkerPtr marker, const GripperMarker::GripperMarkerState &state) |
void | visibleAxisChanged (int state) |
Public Member Functions | |
MainWindow (int argc, char **argv, QWidget *parent=0) | |
~MainWindow () | |
Private Types | |
typedef std::map< std::string, GripperMarkerPtr > | GoalPoseMap |
typedef std::pair< std::string, GripperMarkerPtr > | GoalPosePair |
typedef std::pair < visualization_msgs::InteractiveMarker, boost::shared_ptr < rviz::InteractiveMarker > > | MsgMarkerPair |
typedef std::map< std::string, StartStatePtr > | StartStateMap |
typedef std::pair< std::string, StartStatePtr > | StartStatePair |
enum | StatusType { STATUS_WARN, STATUS_ERROR, STATUS_INFO } |
typedef std::map< std::string, TrajectoryPtr > | TrajectoryMap |
typedef std::pair< std::string, TrajectoryPtr > | TrajectoryPair |
Private Member Functions | |
void | animateTrajectory (const std::vector< robot_state::RobotStatePtr > &traj) |
void | checkIfGoalInCollision (const std::string &goal_name) |
void | checkIfGoalReachable (const std::string &goal_name, bool update_if_reachable=false) |
void | computeGoalPoseDoubleClicked (QListWidgetItem *item) |
void | computeLoadBenchmarkResults (const std::string &file) |
bool | configure () |
void | createTrajectoryStartMarker (const GripperMarker &marker) |
bool | isGroupCollidingWithWorld (robot_state::RobotState &robot_state, const std::string &group_name) |
Return true if any links of the given group_name are in collision with objects in the world (not including the rest of the robot). | |
bool | isIKSolutionCollisionFree (robot_state::RobotState *state, const robot_model::JointModelGroup *group, const double *ik_solution) |
void | loadNewRobot (const std::string &urdf_path, const std::string &srdf_path) |
void | loadSceneButtonClickedBackgroundJob (void) |
MOVEIT_CLASS_FORWARD (StartState) | |
void | populateGoalPosesList () |
void | populatePlanningSceneList (void) |
void | populateStartStatesList () |
void | populateTrajectoriesList () |
void | saveGoalsToDB () |
void | scheduleStateUpdate () |
void | scheduleStateUpdateBackgroundJob () |
void | selectItemJob (QListWidgetItem *item, bool flag) |
void | setItemSelectionInList (const std::string &item_name, bool selection, QListWidget *list) |
void | setStatus (StatusType st, const QString &text) |
void | setStatusFromBackground (StatusType st, const QString &text) |
void | switchGoalPoseMarkerSelection (const std::string &marker_name) |
void | switchTrajectorySelection (const std::string &marker_name) |
void | updateGoalPoseMarkers (float wall_dt, float ros_dt) |
bool | waitForPlanningSceneMonitor (moveit_rviz_plugin::PlanningSceneDisplay *scene_display) |
Private Attributes | |
QDialog * | bbox_dialog_ |
Ui_BoundingBoxGoalsDialog | bbox_dialog_ui_ |
moveit_warehouse::ConstraintsStoragePtr | constraints_storage_ |
std::string | database_host_ |
std::size_t | database_port_ |
Eigen::Affine3d | drag_initial_pose_ |
Eigen::Affine3d | goal_offset_ |
bool | goal_pose_dragging_ |
GoalPoseMap | goal_poses_ |
EigenSTL::map_string_Affine3d | goals_dragging_initial_pose_ |
EigenSTL::map_string_Affine3d | goals_initial_pose_ |
rviz::Display * | int_marker_display_ |
Ui_RobotLoader | load_robot_ui_ |
boost::shared_ptr< QTimer > | main_loop_jobs_timer_ |
moveit_warehouse::PlanningSceneStoragePtr | planning_scene_storage_ |
robot_interaction::RobotInteraction::InteractionHandlerPtr | query_goal_state_ |
rviz::RenderPanel * | render_panel_ |
robot_interaction::RobotInteractionPtr | robot_interaction_ |
QDialog * | robot_loader_dialog_ |
moveit_warehouse::RobotStateStoragePtr | robot_state_storage_ |
QDialog * | run_benchmark_dialog_ |
Ui_BenchmarkDialog | run_benchmark_ui_ |
moveit_rviz_plugin::PlanningSceneDisplay * | scene_display_ |
boost::shared_ptr< QSettings > | settings_ |
StartStateMap | start_states_ |
TrajectoryMap | trajectories_ |
moveit_warehouse::TrajectoryConstraintsStoragePtr | trajectory_constraints_storage_ |
Ui::MainWindow | ui_ |
rviz::VisualizationManager * | visualization_manager_ |
Static Private Attributes | |
static const unsigned int | DEFAULT_WAREHOUSE_PORT = 33830 |
static const unsigned int | MAIN_LOOP_RATE = 20 |
static const char * | ROBOT_DESCRIPTION_PARAM = "robot_description" |
static const char * | ROBOT_DESCRIPTION_SEMANTIC_PARAM = "robot_description_semantic" |
Definition at line 75 of file main_window.h.
typedef std::map<std::string, GripperMarkerPtr> benchmark_tool::MainWindow::GoalPoseMap [private] |
Definition at line 195 of file main_window.h.
typedef std::pair<std::string, GripperMarkerPtr> benchmark_tool::MainWindow::GoalPosePair [private] |
Definition at line 196 of file main_window.h.
typedef std::pair<visualization_msgs::InteractiveMarker, boost::shared_ptr<rviz::InteractiveMarker> > benchmark_tool::MainWindow::MsgMarkerPair [private] |
Definition at line 227 of file main_window.h.
typedef std::map<std::string, StartStatePtr> benchmark_tool::MainWindow::StartStateMap [private] |
Definition at line 218 of file main_window.h.
typedef std::pair<std::string, StartStatePtr> benchmark_tool::MainWindow::StartStatePair [private] |
Definition at line 219 of file main_window.h.
typedef std::map<std::string, TrajectoryPtr> benchmark_tool::MainWindow::TrajectoryMap [private] |
Definition at line 247 of file main_window.h.
typedef std::pair<std::string, TrajectoryPtr> benchmark_tool::MainWindow::TrajectoryPair [private] |
Definition at line 248 of file main_window.h.
enum benchmark_tool::MainWindow::StatusType [private] |
Definition at line 261 of file main_window.h.
benchmark_tool::MainWindow::MainWindow | ( | int | argc, |
char ** | argv, | ||
QWidget * | parent = 0 |
||
) |
Definition at line 57 of file main_window.cpp.
Definition at line 252 of file main_window.cpp.
void benchmark_tool::MainWindow::animateTrajectory | ( | const std::vector< robot_state::RobotStatePtr > & | traj | ) | [private] |
Definition at line 371 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::benchmarkFolderButtonClicked | ( | void | ) | [slot] |
Definition at line 1027 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::cancelBenchmarkButtonClicked | ( | void | ) | [slot] |
Definition at line 1034 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::checkGoalsInCollision | ( | void | ) | [slot] |
Definition at line 681 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::checkGoalsReachable | ( | void | ) | [slot] |
Definition at line 675 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::checkIfGoalInCollision | ( | const std::string & | goal_name | ) | [private] |
Definition at line 768 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::checkIfGoalReachable | ( | const std::string & | goal_name, |
bool | update_if_reachable = false |
||
) | [private] |
Definition at line 687 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::computeGoalPoseDoubleClicked | ( | QListWidgetItem * | item | ) | [private] |
Definition at line 557 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::computeLoadBenchmarkResults | ( | const std::string & | file | ) | [private] |
Definition at line 1159 of file tab_states_and_goals.cpp.
bool benchmark_tool::MainWindow::configure | ( | ) | [private] |
Definition at line 414 of file main_window.cpp.
void benchmark_tool::MainWindow::copySelectedGoalPoses | ( | void | ) | [slot] |
Definition at line 821 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::createBBoxGoalsButtonClicked | ( | void | ) | [slot] |
Definition at line 209 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::createGoalAtPose | ( | const std::string & | name, |
const Eigen::Affine3d & | pose | ||
) | [slot] |
Definition at line 64 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::createGoalPoseButtonClicked | ( | void | ) | [slot] |
Definition at line 141 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::createTrajectoryButtonClicked | ( | void | ) | [slot] |
Definition at line 51 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::createTrajectoryStartMarker | ( | const GripperMarker & | marker | ) | [private] |
void benchmark_tool::MainWindow::dbConnectButtonClicked | ( | ) | [slot] |
Definition at line 594 of file main_window.cpp.
void benchmark_tool::MainWindow::dbConnectButtonClickedBackgroundJob | ( | ) | [slot] |
Definition at line 599 of file main_window.cpp.
void benchmark_tool::MainWindow::deleteGoalsOnDBButtonClicked | ( | void | ) | [slot] |
Definition at line 341 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::deleteStatesOnDBButtonClicked | ( | void | ) | [slot] |
Definition at line 450 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::exitActionTriggered | ( | bool | ) | [slot] |
Definition at line 270 of file main_window.cpp.
void benchmark_tool::MainWindow::goalOffsetChanged | ( | ) | [slot] |
Definition at line 1342 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::goalPoseDoubleClicked | ( | QListWidgetItem * | item | ) | [slot] |
Definition at line 552 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::goalPoseFeedback | ( | visualization_msgs::InteractiveMarkerFeedback & | feedback | ) | [slot] |
Definition at line 572 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::goalPoseSelectionChanged | ( | void | ) | [slot] |
Definition at line 540 of file tab_states_and_goals.cpp.
bool benchmark_tool::MainWindow::isGroupCollidingWithWorld | ( | robot_state::RobotState & | robot_state, |
const std::string & | group_name | ||
) | [private] |
Return true if any links of the given group_name are in collision with objects in the world (not including the rest of the robot).
This function helps display collision state for a disconnected end-effector which is used to show goal poses.
Definition at line 736 of file tab_states_and_goals.cpp.
bool benchmark_tool::MainWindow::isIKSolutionCollisionFree | ( | robot_state::RobotState * | state, |
const robot_model::JointModelGroup * | group, | ||
const double * | ik_solution | ||
) | [private] |
Definition at line 570 of file main_window.cpp.
void benchmark_tool::MainWindow::loadBenchmarkResults | ( | void | ) | [slot] |
Definition at line 1148 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::loadGoalsFromDBButtonClicked | ( | void | ) | [slot] |
Definition at line 260 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::loadNewRobot | ( | const std::string & | urdf_path, |
const std::string & | srdf_path | ||
) | [private] |
Definition at line 292 of file main_window.cpp.
void benchmark_tool::MainWindow::loadSceneButtonClicked | ( | void | ) | [slot] |
Definition at line 723 of file main_window.cpp.
void benchmark_tool::MainWindow::loadSceneButtonClicked | ( | QListWidgetItem * | item | ) | [slot] |
Definition at line 718 of file main_window.cpp.
void benchmark_tool::MainWindow::loadSceneButtonClickedBackgroundJob | ( | void | ) | [private] |
Definition at line 736 of file main_window.cpp.
void benchmark_tool::MainWindow::loadStatesFromDBButtonClicked | ( | void | ) | [slot] |
Definition at line 377 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::loadTrajectoriesFromDBButtonClicked | ( | void | ) | [slot] |
Definition at line 176 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::MainLoop | ( | ) | [slot] |
Definition at line 811 of file main_window.cpp.
benchmark_tool::MainWindow::MOVEIT_CLASS_FORWARD | ( | StartState | ) | [private] |
void benchmark_tool::MainWindow::openActionTriggered | ( | bool | ) | [slot] |
Definition at line 275 of file main_window.cpp.
void benchmark_tool::MainWindow::planningGroupChanged | ( | const QString & | text | ) | [slot] |
Definition at line 519 of file main_window.cpp.
void benchmark_tool::MainWindow::populateGoalPosesList | ( | void | ) | [private] |
Definition at line 500 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::populatePlanningSceneList | ( | void | ) | [private] |
Definition at line 700 of file main_window.cpp.
void benchmark_tool::MainWindow::populateStartStatesList | ( | void | ) | [private] |
Definition at line 939 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::populateTrajectoriesList | ( | void | ) | [private] |
Definition at line 110 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::removeAllGoalsButtonClicked | ( | void | ) | [slot] |
Definition at line 253 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::removeAllStatesButtonClicked | ( | void | ) | [slot] |
Definition at line 933 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::removeSelectedGoalsButtonClicked | ( | void | ) | [slot] |
Definition at line 243 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::removeSelectedStatesButtonClicked | ( | void | ) | [slot] |
Definition at line 923 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::removeTrajectoryButtonClicked | ( | void | ) | [slot] |
Definition at line 139 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::robotInteractionButtonClicked | ( | ) | [slot] |
Definition at line 546 of file main_window.cpp.
void benchmark_tool::MainWindow::runBenchmark | ( | void | ) | [slot] |
Definition at line 960 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::runBenchmarkButtonClicked | ( | void | ) | [slot] |
Definition at line 1087 of file tab_states_and_goals.cpp.
bool benchmark_tool::MainWindow::saveBenchmarkConfigButtonClicked | ( | void | ) | [slot] |
Definition at line 1039 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::saveGoalsOnDBButtonClicked | ( | void | ) | [slot] |
Definition at line 336 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::saveGoalsToDB | ( | ) | [private] |
Definition at line 88 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::saveStartStateButtonClicked | ( | void | ) | [slot] |
Definition at line 875 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::saveStatesOnDBButtonClicked | ( | void | ) | [slot] |
Definition at line 429 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::saveTrajectoriesOnDBButtonClicked | ( | void | ) | [slot] |
Definition at line 276 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::scheduleStateUpdate | ( | ) | [private] |
Definition at line 583 of file main_window.cpp.
void benchmark_tool::MainWindow::scheduleStateUpdateBackgroundJob | ( | ) | [private] |
Definition at line 588 of file main_window.cpp.
void benchmark_tool::MainWindow::selectItemJob | ( | QListWidgetItem * | item, |
bool | flag | ||
) | [private] |
Definition at line 819 of file main_window.cpp.
void benchmark_tool::MainWindow::setItemSelectionInList | ( | const std::string & | item_name, |
bool | selection, | ||
QListWidget * | list | ||
) | [private] |
Definition at line 824 of file main_window.cpp.
void benchmark_tool::MainWindow::setStatus | ( | StatusType | st, |
const QString & | text | ||
) | [inline, private] |
Definition at line 262 of file main_window.h.
void benchmark_tool::MainWindow::setStatusFromBackground | ( | StatusType | st, |
const QString & | text | ||
) | [inline, private] |
Definition at line 280 of file main_window.h.
void benchmark_tool::MainWindow::showBBoxGoalsDialog | ( | ) | [slot] |
Definition at line 188 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::startStateItemDoubleClicked | ( | QListWidgetItem * | item | ) | [slot] |
Definition at line 954 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::switchGoalPoseMarkerSelection | ( | const std::string & | marker_name | ) | [private] |
Definition at line 799 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::switchGoalVisibilityButtonClicked | ( | void | ) | [slot] |
Definition at line 519 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::switchTrajectorySelection | ( | const std::string & | marker_name | ) | [private] |
void benchmark_tool::MainWindow::trajectoryExecuteButtonClicked | ( | void | ) | [slot] |
Definition at line 340 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::trajectoryNWaypointsChanged | ( | int | n | ) | [slot] |
Definition at line 331 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::trajectorySelectionChanged | ( | void | ) | [slot] |
Definition at line 122 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::updateGoalMarkerStateFromName | ( | const std::string & | name, |
const GripperMarker::GripperMarkerState & | state | ||
) | [slot] |
Definition at line 1331 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::updateGoalPoseMarkers | ( | float | wall_dt, |
float | ros_dt | ||
) | [private] |
Definition at line 791 of file main_window.cpp.
void benchmark_tool::MainWindow::updateMarkerState | ( | GripperMarkerPtr | marker, |
const GripperMarker::GripperMarkerState & | state | ||
) | [slot] |
Definition at line 1337 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::visibleAxisChanged | ( | int | state | ) | [slot] |
Definition at line 485 of file tab_states_and_goals.cpp.
bool benchmark_tool::MainWindow::waitForPlanningSceneMonitor | ( | moveit_rviz_plugin::PlanningSceneDisplay * | scene_display | ) | [private] |
Definition at line 256 of file main_window.cpp.
QDialog * benchmark_tool::MainWindow::bbox_dialog_ [private] |
Definition at line 153 of file main_window.h.
Ui_BoundingBoxGoalsDialog benchmark_tool::MainWindow::bbox_dialog_ui_ [private] |
Definition at line 152 of file main_window.h.
moveit_warehouse::ConstraintsStoragePtr benchmark_tool::MainWindow::constraints_storage_ [private] |
Definition at line 180 of file main_window.h.
std::string benchmark_tool::MainWindow::database_host_ [private] |
Definition at line 177 of file main_window.h.
std::size_t benchmark_tool::MainWindow::database_port_ [private] |
Definition at line 178 of file main_window.h.
const unsigned int benchmark_tool::MainWindow::DEFAULT_WAREHOUSE_PORT = 33830 [static, private] |
Definition at line 147 of file main_window.h.
Eigen::Affine3d benchmark_tool::MainWindow::drag_initial_pose_ [private] |
Definition at line 193 of file main_window.h.
Eigen::Affine3d benchmark_tool::MainWindow::goal_offset_ [private] |
Definition at line 189 of file main_window.h.
bool benchmark_tool::MainWindow::goal_pose_dragging_ [private] |
Definition at line 192 of file main_window.h.
Definition at line 197 of file main_window.h.
Definition at line 191 of file main_window.h.
Definition at line 190 of file main_window.h.
Definition at line 174 of file main_window.h.
Ui_RobotLoader benchmark_tool::MainWindow::load_robot_ui_ [private] |
Definition at line 151 of file main_window.h.
boost::shared_ptr<QTimer> benchmark_tool::MainWindow::main_loop_jobs_timer_ [private] |
Definition at line 258 of file main_window.h.
const unsigned int benchmark_tool::MainWindow::MAIN_LOOP_RATE = 20 [static, private] |
Definition at line 257 of file main_window.h.
moveit_warehouse::PlanningSceneStoragePtr benchmark_tool::MainWindow::planning_scene_storage_ [private] |
Definition at line 179 of file main_window.h.
robot_interaction::RobotInteraction::InteractionHandlerPtr benchmark_tool::MainWindow::query_goal_state_ [private] |
Definition at line 187 of file main_window.h.
Definition at line 157 of file main_window.h.
const char * benchmark_tool::MainWindow::ROBOT_DESCRIPTION_PARAM = "robot_description" [static, private] |
Definition at line 145 of file main_window.h.
const char * benchmark_tool::MainWindow::ROBOT_DESCRIPTION_SEMANTIC_PARAM = "robot_description_semantic" [static, private] |
Definition at line 146 of file main_window.h.
robot_interaction::RobotInteractionPtr benchmark_tool::MainWindow::robot_interaction_ [private] |
Definition at line 173 of file main_window.h.
QDialog* benchmark_tool::MainWindow::robot_loader_dialog_ [private] |
Definition at line 153 of file main_window.h.
moveit_warehouse::RobotStateStoragePtr benchmark_tool::MainWindow::robot_state_storage_ [private] |
Definition at line 182 of file main_window.h.
QDialog * benchmark_tool::MainWindow::run_benchmark_dialog_ [private] |
Definition at line 153 of file main_window.h.
Ui_BenchmarkDialog benchmark_tool::MainWindow::run_benchmark_ui_ [private] |
Definition at line 150 of file main_window.h.
Definition at line 159 of file main_window.h.
boost::shared_ptr<QSettings> benchmark_tool::MainWindow::settings_ [private] |
Definition at line 154 of file main_window.h.
Definition at line 220 of file main_window.h.
Definition at line 249 of file main_window.h.
moveit_warehouse::TrajectoryConstraintsStoragePtr benchmark_tool::MainWindow::trajectory_constraints_storage_ [private] |
Definition at line 181 of file main_window.h.
Ui::MainWindow benchmark_tool::MainWindow::ui_ [private] |
Definition at line 149 of file main_window.h.
Definition at line 158 of file main_window.h.