Skip to content

Commit

Permalink
some suggested changes to GUI text
Browse files Browse the repository at this point in the history
  • Loading branch information
John Stechschulte authored and RoboticsYY committed Jun 8, 2020
1 parent f9b4f55 commit b05ce3c
Show file tree
Hide file tree
Showing 3 changed files with 35 additions and 35 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -171,9 +171,9 @@ ContextTabWidget::ContextTabWidget(QWidget* parent) : QWidget(parent), tf_listen
group_left_top->setLayout(layout_left_top);

sensor_mount_type_ = new QComboBox();
sensor_mount_type_->addItem("Eye-to-Hand");
sensor_mount_type_->addItem("Eye-to-hand");
sensor_mount_type_->addItem("Eye-in-hand");
layout_left_top->addRow("Sensor Mount Type", sensor_mount_type_);
layout_left_top->addRow("Sensor configuration", sensor_mount_type_);
connect(sensor_mount_type_, SIGNAL(activated(int)), this, SLOT(updateSensorMountType(int)));

// Frame name selection area
Expand All @@ -183,16 +183,16 @@ ContextTabWidget::ContextTabWidget(QWidget* parent) : QWidget(parent), tf_listen
frame_group->setLayout(frame_layout);

frames_.insert(std::make_pair("sensor", new TFFrameNameComboBox(CAMERA_FRAME)));
frame_layout->addRow("Sensor Frame:", frames_["sensor"]);
frame_layout->addRow("Sensor frame:", frames_["sensor"]);

frames_.insert(std::make_pair("object", new TFFrameNameComboBox(ENVIRONMENT_FRAME)));
frame_layout->addRow("Object Frame:", frames_["object"]);
frame_layout->addRow("Object frame:", frames_["object"]);

frames_.insert(std::make_pair("eef", new TFFrameNameComboBox(ROBOT_FRAME)));
frame_layout->addRow("End-Effector Frame:", frames_["eef"]);
frame_layout->addRow("End-effector frame:", frames_["eef"]);

frames_.insert(std::make_pair("base", new TFFrameNameComboBox(ROBOT_FRAME)));
frame_layout->addRow("Robot Base Frame:", frames_["base"]);
frame_layout->addRow("Robot base frame:", frames_["base"]);

for (std::pair<const std::string, TFFrameNameComboBox*>& frame : frames_)
connect(frame.second, SIGNAL(activated(int)), this, SLOT(updateFrameName(int)));
Expand Down Expand Up @@ -220,22 +220,22 @@ ContextTabWidget::ContextTabWidget(QWidget* parent) : QWidget(parent), tf_listen
QFormLayout* pose_layout = new QFormLayout();
pose_group->setLayout(pose_layout);

guess_pose_.insert(std::make_pair("Tx", new SliderWidget(this, "TranslX", -2.0, 2.0)));
guess_pose_.insert(std::make_pair("Tx", new SliderWidget(this, "X", -2.0, 2.0)));
pose_layout->addRow(guess_pose_["Tx"]);

guess_pose_.insert(std::make_pair("Ty", new SliderWidget(this, "TranslY", -2.0, 2.0)));
guess_pose_.insert(std::make_pair("Ty", new SliderWidget(this, "Y", -2.0, 2.0)));
pose_layout->addRow(guess_pose_["Ty"]);

guess_pose_.insert(std::make_pair("Tz", new SliderWidget(this, "TranslZ", -2.0, 2.0)));
guess_pose_.insert(std::make_pair("Tz", new SliderWidget(this, "Z", -2.0, 2.0)));
pose_layout->addRow(guess_pose_["Tz"]);

guess_pose_.insert(std::make_pair("Rx", new SliderWidget(this, "RotateX", -M_PI, M_PI)));
guess_pose_.insert(std::make_pair("Rx", new SliderWidget(this, "Roll", -M_PI, M_PI)));
pose_layout->addRow(guess_pose_["Rx"]);

guess_pose_.insert(std::make_pair("Ry", new SliderWidget(this, "RotateY", -M_PI, M_PI)));
guess_pose_.insert(std::make_pair("Ry", new SliderWidget(this, "Pitch", -M_PI, M_PI)));
pose_layout->addRow(guess_pose_["Ry"]);

guess_pose_.insert(std::make_pair("Rz", new SliderWidget(this, "RotateZ", -M_PI, M_PI)));
guess_pose_.insert(std::make_pair("Rz", new SliderWidget(this, "Yaw", -M_PI, M_PI)));
pose_layout->addRow(guess_pose_["Rz"]);

for (std::pair<const std::string, SliderWidget*>& dim : guess_pose_)
Expand Down Expand Up @@ -550,4 +550,4 @@ void ContextTabWidget::fovOnOffBtnToggled(bool checked)
updateAllMarkers();
}

} // namgespace moveit_rviz_plugin
} // namgespace moveit_rviz_plugin
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ ControlTabWidget::ControlTabWidget(QWidget* parent)
layout->addWidget(auto_progress_);

// Pose sample tree view area
QGroupBox* sample_group = new QGroupBox("Pose_sample");
QGroupBox* sample_group = new QGroupBox("Pose samples");
sample_group->setMinimumWidth(280);
calib_layout->addWidget(sample_group);
QVBoxLayout* sample_layout = new QVBoxLayout();
Expand All @@ -131,11 +131,11 @@ ControlTabWidget::ControlTabWidget(QWidget* parent)
sample_tree_view_->setIndentation(10);
sample_layout->addWidget(sample_tree_view_);

// Setting area
// Settings area
QVBoxLayout* layout_right = new QVBoxLayout();
calib_layout->addLayout(layout_right);

QGroupBox* setting_group = new QGroupBox("Setting");
QGroupBox* setting_group = new QGroupBox("Settings");
layout_right->addWidget(setting_group);
QFormLayout* setting_layout = new QFormLayout();
setting_group->setLayout(setting_layout);
Expand All @@ -147,15 +147,15 @@ ControlTabWidget::ControlTabWidget(QWidget* parent)
connect(group_name_, SIGNAL(activated(const QString&)), this, SLOT(planningGroupNameChanged(const QString&)));
setting_layout->addRow("Planning Group", group_name_);

load_joint_state_btn_ = new QPushButton("Load Joint States");
load_joint_state_btn_ = new QPushButton("Load joint states");
connect(load_joint_state_btn_, SIGNAL(clicked(bool)), this, SLOT(loadJointStateBtnClicked(bool)));
setting_layout->addRow(load_joint_state_btn_);

save_joint_state_btn_ = new QPushButton("Save Joint states");
save_joint_state_btn_ = new QPushButton("Save joint states");
connect(save_joint_state_btn_, SIGNAL(clicked(bool)), this, SLOT(saveJointStateBtnClicked(bool)));
setting_layout->addRow(save_joint_state_btn_);

save_camera_pose_btn_ = new QPushButton("Save Camera Pose");
save_camera_pose_btn_ = new QPushButton("Save camera pose");
connect(save_camera_pose_btn_, SIGNAL(clicked(bool)), this, SLOT(saveCameraPoseBtnClicked(bool)));
setting_layout->addRow(save_camera_pose_btn_);

Expand All @@ -165,12 +165,12 @@ ControlTabWidget::ControlTabWidget(QWidget* parent)
QHBoxLayout* control_cal_layout = new QHBoxLayout();
manual_cal_group->setLayout(control_cal_layout);

take_sample_btn_ = new QPushButton("Take Sample");
take_sample_btn_ = new QPushButton("Take sample");
take_sample_btn_->setMinimumHeight(35);
connect(take_sample_btn_, SIGNAL(clicked(bool)), this, SLOT(takeSampleBtnClicked(bool)));
control_cal_layout->addWidget(take_sample_btn_);

reset_sample_btn_ = new QPushButton("Reset Sample");
reset_sample_btn_ = new QPushButton("Reset samples");
reset_sample_btn_->setMinimumHeight(35);
connect(reset_sample_btn_, SIGNAL(clicked(bool)), this, SLOT(resetSampleBtnClicked(bool)));
control_cal_layout->addWidget(reset_sample_btn_);
Expand Down Expand Up @@ -430,12 +430,12 @@ void ControlTabWidget::addPoseSampleToTreeView(const geometry_msgs::TransformSta

std::ostringstream ss;

QStandardItem* child_1 = new QStandardItem("bTe");
QStandardItem* child_1 = new QStandardItem("TF base-to-eef");
ss << bTe.transform;
child_1->appendRow(new QStandardItem(ss.str().c_str()));
parent->appendRow(child_1);

QStandardItem* child_2 = new QStandardItem("cTo");
QStandardItem* child_2 = new QStandardItem("TF camera-to-target");
ss.str("");
ss << cTo.transform;
child_2->appendRow(new QStandardItem(ss.str().c_str()));
Expand Down Expand Up @@ -825,4 +825,4 @@ void ControlTabWidget::autoSkipBtnClicked(bool clicked)
auto_progress_->setValue(auto_progress_->getValue() + 1);
}

} // namespace moveit_rviz_plugin
} // namespace moveit_rviz_plugin
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ TargetTabWidget::TargetTabWidget(QWidget* parent)
layout->addLayout(layout_left);

// Target creation area
QGroupBox* group_left_top = new QGroupBox("Target_Intrinsic_Params", this);
QGroupBox* group_left_top = new QGroupBox("Target Intrinsic Params", this);
layout_left->addWidget(group_left_top);
QFormLayout* layout_left_top = new QFormLayout();
group_left_top->setLayout(layout_left_top);
Expand All @@ -115,26 +115,26 @@ TargetTabWidget::TargetTabWidget(QWidget* parent)

target_params_["markers_x"]->setText(QString("4"));
target_params_["markers_x"]->setValidator(new QIntValidator(1, 50));
layout_left_top->addRow("Num_Markers_X", target_params_["markers_x"]);
layout_left_top->addRow("Num markers, X", target_params_["markers_x"]);

target_params_["markers_y"]->setText(QString("5"));
target_params_["markers_y"]->setValidator(new QIntValidator(1, 50));
layout_left_top->addRow("Num_Markers_Y", target_params_["markers_y"]);
layout_left_top->addRow("Num markers, Y", target_params_["markers_y"]);

target_params_["marker_size"]->setText(QString("200"));
target_params_["marker_size"]->setValidator(new QIntValidator(100, 1000));
layout_left_top->addRow("Marker_Size_(pixels)", target_params_["marker_size"]);
layout_left_top->addRow("Marker size (pixels)", target_params_["marker_size"]);

target_params_["marker_dist"]->setText(QString("20"));
target_params_["marker_dist"]->setValidator(new QIntValidator(10, 200));
layout_left_top->addRow("Marker_Dist_(pixels)", target_params_["marker_dist"]);
layout_left_top->addRow("Marker spacing (pixels)", target_params_["marker_dist"]);

target_params_["marker_border"]->setText(QString("1"));
target_params_["marker_border"]->setValidator(new QIntValidator(1, 4));
layout_left_top->addRow("Marker_Border_(bits)", target_params_["marker_border"]);
layout_left_top->addRow("Marker border (bits)", target_params_["marker_border"]);

// Target 3D pose recognition area
QGroupBox* group_left_bottom = new QGroupBox("Target_Pose_Recognition", this);
QGroupBox* group_left_bottom = new QGroupBox("Target Pose Detection", this);
layout_left->addWidget(group_left_bottom);
QFormLayout* layout_left_bottom = new QFormLayout();
group_left_bottom->setLayout(layout_left_bottom);
Expand All @@ -156,14 +156,14 @@ TargetTabWidget::TargetTabWidget(QWidget* parent)

target_real_dims_["marker_size_real"]->setText("0.0256");
target_real_dims_["marker_size_real"]->setValidator(new QDoubleValidator(0, 2, 4));
layout_left_bottom->addRow("Marker Size (m)", target_real_dims_["marker_size_real"]);
layout_left_bottom->addRow("Marker size (m)", target_real_dims_["marker_size_real"]);

target_real_dims_["marker_dist_real"]->setText("0.0066");
target_real_dims_["marker_dist_real"]->setValidator(new QDoubleValidator(0, 2, 4));
layout_left_bottom->addRow("Marker Dist (m)", target_real_dims_["marker_dist_real"]);
layout_left_bottom->addRow("Marker spacing (m)", target_real_dims_["marker_dist_real"]);

// Target image dislay, create and save area
QGroupBox* group_right = new QGroupBox("Target_Create_Save", this);
QGroupBox* group_right = new QGroupBox("Target", this);
group_right->setMinimumWidth(330);
layout->addWidget(group_right);
QVBoxLayout* layout_right = new QVBoxLayout();
Expand Down Expand Up @@ -535,4 +535,4 @@ void TargetTabWidget::cameraInfoComboBoxChanged(const QString& topic)
}
}

} // namedist moveit_rviz_plugin
} // namedist moveit_rviz_plugin

0 comments on commit b05ce3c

Please sign in to comment.