#include <main_window.h>
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 220 of file main_window.h.
typedef std::map<std::string, StartStatePtr> benchmark_tool::MainWindow::StartStateMap [private] |
Definition at line 211 of file main_window.h.
typedef std::pair<std::string, StartStatePtr> benchmark_tool::MainWindow::StartStatePair [private] |
Definition at line 212 of file main_window.h.
typedef boost::shared_ptr<StartState> benchmark_tool::MainWindow::StartStatePtr [private] |
Definition at line 209 of file main_window.h.
typedef std::map<std::string, TrajectoryPtr> benchmark_tool::MainWindow::TrajectoryMap [private] |
Definition at line 240 of file main_window.h.
typedef std::pair<std::string, TrajectoryPtr> benchmark_tool::MainWindow::TrajectoryPair [private] |
Definition at line 241 of file main_window.h.
enum benchmark_tool::MainWindow::StatusType [private] |
Definition at line 254 of file main_window.h.
benchmark_tool::MainWindow::MainWindow | ( | int | argc, |
char ** | argv, | ||
QWidget * | parent = 0 |
||
) |
Definition at line 58 of file main_window.cpp.
Definition at line 232 of file main_window.cpp.
void benchmark_tool::MainWindow::animateTrajectory | ( | const std::vector< boost::shared_ptr< robot_state::RobotState > > & | traj | ) | [private] |
Definition at line 354 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::benchmarkFolderButtonClicked | ( | void | ) | [slot] |
Definition at line 1007 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::cancelBenchmarkButtonClicked | ( | void | ) | [slot] |
Definition at line 1014 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::checkGoalsInCollision | ( | void | ) | [slot] |
Definition at line 666 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::checkGoalsReachable | ( | void | ) | [slot] |
Definition at line 660 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::checkIfGoalInCollision | ( | const std::string & | goal_name | ) | [private] |
Definition at line 754 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 672 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::computeGoalPoseDoubleClicked | ( | QListWidgetItem * | item | ) | [private] |
Definition at line 546 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::computeLoadBenchmarkResults | ( | const std::string & | file | ) | [private] |
Definition at line 1126 of file tab_states_and_goals.cpp.
bool benchmark_tool::MainWindow::configure | ( | ) | [private] |
Definition at line 388 of file main_window.cpp.
void benchmark_tool::MainWindow::copySelectedGoalPoses | ( | void | ) | [slot] |
Definition at line 807 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::createBBoxGoalsButtonClicked | ( | void | ) | [slot] |
Definition at line 204 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::createGoalAtPose | ( | const std::string & | name, |
const Eigen::Affine3d & | pose | ||
) | [slot] |
Definition at line 65 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::createGoalPoseButtonClicked | ( | void | ) | [slot] |
Definition at line 140 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::createTrajectoryButtonClicked | ( | void | ) | [slot] |
Definition at line 52 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::createTrajectoryStartMarker | ( | const GripperMarker & | marker | ) | [private] |
void benchmark_tool::MainWindow::dbConnectButtonClicked | ( | ) | [slot] |
Definition at line 557 of file main_window.cpp.
void benchmark_tool::MainWindow::dbConnectButtonClickedBackgroundJob | ( | ) | [slot] |
Definition at line 562 of file main_window.cpp.
void benchmark_tool::MainWindow::deleteGoalsOnDBButtonClicked | ( | void | ) | [slot] |
Definition at line 330 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::deleteStatesOnDBButtonClicked | ( | void | ) | [slot] |
Definition at line 439 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::exitActionTriggered | ( | bool | ) | [slot] |
Definition at line 250 of file main_window.cpp.
void benchmark_tool::MainWindow::goalOffsetChanged | ( | ) | [slot] |
Definition at line 1302 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::goalPoseDoubleClicked | ( | QListWidgetItem * | item | ) | [slot] |
Definition at line 541 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::goalPoseFeedback | ( | visualization_msgs::InteractiveMarkerFeedback & | feedback | ) | [slot] |
Definition at line 560 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::goalPoseSelectionChanged | ( | void | ) | [slot] |
Definition at line 528 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 722 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 534 of file main_window.cpp.
void benchmark_tool::MainWindow::loadBenchmarkResults | ( | void | ) | [slot] |
Definition at line 1116 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::loadGoalsFromDBButtonClicked | ( | void | ) | [slot] |
Definition at line 254 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 270 of file main_window.cpp.
void benchmark_tool::MainWindow::loadSceneButtonClicked | ( | void | ) | [slot] |
Definition at line 669 of file main_window.cpp.
void benchmark_tool::MainWindow::loadSceneButtonClicked | ( | QListWidgetItem * | item | ) | [slot] |
Definition at line 664 of file main_window.cpp.
void benchmark_tool::MainWindow::loadSceneButtonClickedBackgroundJob | ( | void | ) | [private] |
Definition at line 681 of file main_window.cpp.
void benchmark_tool::MainWindow::loadStatesFromDBButtonClicked | ( | void | ) | [slot] |
Definition at line 367 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::loadTrajectoriesFromDBButtonClicked | ( | void | ) | [slot] |
Definition at line 173 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::MainLoop | ( | ) | [slot] |
Definition at line 756 of file main_window.cpp.
void benchmark_tool::MainWindow::openActionTriggered | ( | bool | ) | [slot] |
Definition at line 255 of file main_window.cpp.
void benchmark_tool::MainWindow::planningGroupChanged | ( | const QString & | text | ) | [slot] |
Definition at line 488 of file main_window.cpp.
void benchmark_tool::MainWindow::populateGoalPosesList | ( | void | ) | [private] |
Definition at line 488 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::populatePlanningSceneList | ( | void | ) | [private] |
Definition at line 646 of file main_window.cpp.
void benchmark_tool::MainWindow::populateStartStatesList | ( | void | ) | [private] |
Definition at line 921 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::populateTrajectoriesList | ( | void | ) | [private] |
Definition at line 107 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::removeAllGoalsButtonClicked | ( | void | ) | [slot] |
Definition at line 247 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::removeAllStatesButtonClicked | ( | void | ) | [slot] |
Definition at line 915 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::removeSelectedGoalsButtonClicked | ( | void | ) | [slot] |
Definition at line 237 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::removeSelectedStatesButtonClicked | ( | void | ) | [slot] |
Definition at line 905 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::removeTrajectoryButtonClicked | ( | void | ) | [slot] |
Definition at line 136 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::robotInteractionButtonClicked | ( | ) | [slot] |
Definition at line 513 of file main_window.cpp.
void benchmark_tool::MainWindow::runBenchmark | ( | void | ) | [slot] |
Definition at line 942 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::runBenchmarkButtonClicked | ( | void | ) | [slot] |
Definition at line 1066 of file tab_states_and_goals.cpp.
bool benchmark_tool::MainWindow::saveBenchmarkConfigButtonClicked | ( | void | ) | [slot] |
Definition at line 1019 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::saveGoalsOnDBButtonClicked | ( | void | ) | [slot] |
Definition at line 325 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::saveGoalsToDB | ( | ) | [private] |
Definition at line 87 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::saveStartStateButtonClicked | ( | void | ) | [slot] |
Definition at line 858 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::saveStatesOnDBButtonClicked | ( | void | ) | [slot] |
Definition at line 418 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::saveTrajectoriesOnDBButtonClicked | ( | void | ) | [slot] |
Definition at line 261 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::scheduleStateUpdate | ( | ) | [private] |
Definition at line 546 of file main_window.cpp.
void benchmark_tool::MainWindow::scheduleStateUpdateBackgroundJob | ( | ) | [private] |
Definition at line 551 of file main_window.cpp.
void benchmark_tool::MainWindow::selectItemJob | ( | QListWidgetItem * | item, |
bool | flag | ||
) | [private] |
Definition at line 764 of file main_window.cpp.
void benchmark_tool::MainWindow::setItemSelectionInList | ( | const std::string & | item_name, |
bool | selection, | ||
QListWidget * | list | ||
) | [private] |
Definition at line 769 of file main_window.cpp.
void benchmark_tool::MainWindow::setStatus | ( | StatusType | st, |
const QString & | text | ||
) | [inline, private] |
Definition at line 255 of file main_window.h.
void benchmark_tool::MainWindow::setStatusFromBackground | ( | StatusType | st, |
const QString & | text | ||
) | [inline, private] |
Definition at line 273 of file main_window.h.
void benchmark_tool::MainWindow::showBBoxGoalsDialog | ( | ) | [slot] |
Definition at line 185 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::startStateItemDoubleClicked | ( | QListWidgetItem * | item | ) | [slot] |
Definition at line 936 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::switchGoalPoseMarkerSelection | ( | const std::string & | marker_name | ) | [private] |
Definition at line 785 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::switchGoalVisibilityButtonClicked | ( | void | ) | [slot] |
Definition at line 507 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 325 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::trajectoryNWaypointsChanged | ( | int | n | ) | [slot] |
Definition at line 316 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::trajectorySelectionChanged | ( | void | ) | [slot] |
Definition at line 119 of file tab_trajectories.cpp.
void benchmark_tool::MainWindow::updateGoalMarkerStateFromName | ( | const std::string & | name, |
const GripperMarker::GripperMarkerState & | state | ||
) | [slot] |
Definition at line 1291 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::updateGoalPoseMarkers | ( | float | wall_dt, |
float | ros_dt | ||
) | [private] |
Definition at line 737 of file main_window.cpp.
void benchmark_tool::MainWindow::updateMarkerState | ( | GripperMarkerPtr | marker, |
const GripperMarker::GripperMarkerState & | state | ||
) | [slot] |
Definition at line 1297 of file tab_states_and_goals.cpp.
void benchmark_tool::MainWindow::visibleAxisChanged | ( | int | state | ) | [slot] |
Definition at line 474 of file tab_states_and_goals.cpp.
bool benchmark_tool::MainWindow::waitForPlanningSceneMonitor | ( | moveit_rviz_plugin::PlanningSceneDisplay * | scene_display | ) | [private] |
Definition at line 236 of file main_window.cpp.
QDialog * benchmark_tool::MainWindow::bbox_dialog_ [private] |
Definition at line 154 of file main_window.h.
Ui_BoundingBoxGoalsDialog benchmark_tool::MainWindow::bbox_dialog_ui_ [private] |
Definition at line 153 of file main_window.h.
boost::shared_ptr<moveit_warehouse::ConstraintsStorage> 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 148 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 152 of file main_window.h.
boost::shared_ptr<QTimer> benchmark_tool::MainWindow::main_loop_jobs_timer_ [private] |
Definition at line 251 of file main_window.h.
const unsigned int benchmark_tool::MainWindow::MAIN_LOOP_RATE = 20 [static, private] |
Definition at line 250 of file main_window.h.
boost::shared_ptr<moveit_warehouse::PlanningSceneStorage> 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 158 of file main_window.h.
const char * benchmark_tool::MainWindow::ROBOT_DESCRIPTION_PARAM = "robot_description" [static, private] |
Definition at line 146 of file main_window.h.
const char * benchmark_tool::MainWindow::ROBOT_DESCRIPTION_SEMANTIC_PARAM = "robot_description_semantic" [static, private] |
Definition at line 147 of file main_window.h.
Definition at line 173 of file main_window.h.
QDialog* benchmark_tool::MainWindow::robot_loader_dialog_ [private] |
Definition at line 154 of file main_window.h.
boost::shared_ptr<moveit_warehouse::RobotStateStorage> 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 154 of file main_window.h.
Ui_BenchmarkDialog benchmark_tool::MainWindow::run_benchmark_ui_ [private] |
Definition at line 151 of file main_window.h.
Definition at line 160 of file main_window.h.
boost::shared_ptr<QSettings> benchmark_tool::MainWindow::settings_ [private] |
Definition at line 155 of file main_window.h.
Definition at line 213 of file main_window.h.
Definition at line 242 of file main_window.h.
boost::shared_ptr<moveit_warehouse::TrajectoryConstraintsStorage> 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 150 of file main_window.h.
Definition at line 159 of file main_window.h.