Skip to content
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

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down Expand Up @@ -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;
Copy link

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

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_)
Copy link

Choose a reason for hiding this comment

The 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 _tf is unnecessary if you don't use _eig. Would still spell out _eigen.

{
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_)
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Missing & (auto&)

{
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());
}
Expand Down