-
Notifications
You must be signed in to change notification settings - Fork 79
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Enforce min rotation between samples #62
base: master
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -39,6 +39,7 @@ | |
namespace moveit_rviz_plugin | ||
{ | ||
const std::string LOGNAME = "handeye_control_widget"; | ||
const double MIN_ROTATION = M_PI / 36.; // Smallest allowed rotation, 5 degrees | ||
|
||
ProgressBarWidget::ProgressBarWidget(QWidget* parent, int min, int max, int value) : QWidget(parent) | ||
{ | ||
|
@@ -370,9 +371,36 @@ bool ControlTabWidget::takeTransformSamples() | |
// Get the transform of the end-effector w.r.t the robot base | ||
base_to_eef_tf = tf_buffer_->lookupTransform(frame_names_["base"], frame_names_["eef"], ros::Time(0)); | ||
|
||
// Verify that sample contains sufficient rotation | ||
Eigen::Isometry3d base_to_eef_eig, camera_to_object_eig; | ||
base_to_eef_eig = tf2::transformToEigen(base_to_eef_tf); | ||
camera_to_object_eig = tf2::transformToEigen(camera_to_object_tf); | ||
|
||
for (const auto& prior_tf : effector_wrt_world_) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Nit: Would use "previous" instead of "prior" to avoid potential mixups with "prior assumptions"/"prior knowledge"_Machine Learning terminology. The suffix |
||
{ | ||
Eigen::AngleAxisd rot((base_to_eef_eig.inverse() * prior_tf).rotation()); | ||
if (rot.angle() < MIN_ROTATION) | ||
{ | ||
QMessageBox::warning(this, tr("Error"), | ||
tr("End-effector orientation is too similar to a prior sample. Sample not recorded.")); | ||
return false; | ||
} | ||
} | ||
|
||
for (const auto prior_tf : object_wrt_sensor_) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Missing & ( |
||
{ | ||
Eigen::AngleAxisd rot((camera_to_object_eig.inverse() * prior_tf).rotation()); | ||
if (rot.angle() < MIN_ROTATION) | ||
{ | ||
QMessageBox::warning(this, tr("Error"), | ||
tr("Camera orientation is too similar to a prior sample. Sample not recorded.")); | ||
return false; | ||
} | ||
} | ||
|
||
// save the pose samples | ||
effector_wrt_world_.push_back(tf2::transformToEigen(base_to_eef_tf)); | ||
object_wrt_sensor_.push_back(tf2::transformToEigen(camera_to_object_tf)); | ||
effector_wrt_world_.push_back(base_to_eef_eig); | ||
object_wrt_sensor_.push_back(camera_to_object_eig); | ||
|
||
ControlTabWidget::addPoseSampleToTreeView(camera_to_object_tf, base_to_eef_tf, effector_wrt_world_.size()); | ||
} | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I'd spell out eigen