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

also check headings in shouldProcessScan #545

Open
wants to merge 1 commit into
base: ros2
Choose a base branch
from

Conversation

981213
Copy link

@981213 981213 commented Oct 25, 2022

This should fix #499 .

@@ -2318,7 +2318,7 @@ double Mapper::getParamMinimumTravelDistance()

double Mapper::getParamMinimumTravelHeading()
{
return math::RadiansToDegrees(static_cast<double>(m_pMinimumTravelHeading->GetValue()));
return static_cast<double>(m_pMinimumTravelHeading->GetValue());
Copy link
Owner

Choose a reason for hiding this comment

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

Don't change the units in the core library

Copy link
Author

Choose a reason for hiding this comment

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

It's confusing that getParamMinimumTravelHeading returns heading in degrees while setParamMinimumTravelHeading takes radians instead. I think it's better to make these two functions return values in the same unit. What do you think?

Copy link
Owner

Choose a reason for hiding this comment

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

I don't disagree, but the karto stuff is very complex and I've learned the hard way not to make changes here unless strictly required for functionality. I don't think there will be any ramifications of this change downstream, but I also don't have the resources to fire-fight major issues in this project right now so I'm being overly cautious

double heading_diff = pose.GetHeading() - last_pose.GetHeading();
if (heading_diff < 0)
heading_diff = -heading_diff;
if ((dist2 < 0.8 * min_dist2 && heading_diff < 0.9 * min_heading) || scan_ctr < 5) {
Copy link
Owner

Choose a reason for hiding this comment

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

Why 0.9? That seems arbitrary

Copy link
Author

Choose a reason for hiding this comment

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

The comment a few lines above said:

// check moved enough, within 10% for correction error

so I followed that by multiplying 0.9.

if (dist2 < 0.8 * min_dist2 || scan_ctr < 5) {
double heading_diff = pose.GetHeading() - last_pose.GetHeading();
if (heading_diff < 0)
heading_diff = -heading_diff;
Copy link
Owner

Choose a reason for hiding this comment

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

You can just use fabs() in the if condition below and remove this

Copy link
Author

Choose a reason for hiding this comment

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

OK.

@JustSomeRandomUsername
Copy link

Is there a reason this has not been merged, it seems like an important change. In my project this pull request has drastically improved the accuracy of the localization. Also is this not basically a duplicate of #451.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

Rotating (pivoting) robot doesn't update map in ROS2 Foxy
3 participants