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

save pose graph when merging map #196

Open
wants to merge 5 commits into
base: melodic-devel
Choose a base branch
from

Conversation

sunrentao
Copy link


Basic Info

Info Please fill out this column
Ticket(s) this addresses
Primary OS tested on (Ubuntu)
Robotic platform tested on ( customized hardware )

Description of contribution in a few bullet points

  • when generate merged map , also generate merged posegraph, but I don't update rviz gui, so only indicate the file name with command line

Description of documentation updates required from your changes

  • rosservice call /map_merging/merge_submaps "filename: ''the name you want"

Future work that may be required in bullet points

  • When merge pose graph, it should work as lifelong to decay old node.

@@ -248,8 +251,24 @@ bool MergeMapsKinematic::mergeMapCallback(
tf2::Transform submap_correction = submap_marker_transform_[id];
transformScan(iter, submap_correction);
transformed_scans.push_back((*iter));

if (iter == it_LRV->begin() && id != 1){
Copy link
Owner

Choose a reason for hiding this comment

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

Please add a space between ) {. Also you didn't indent your if/else code. Finally, remove all spaces between pointer accessors.

slam_toolbox/src/merge_maps_kinematic.cpp Show resolved Hide resolved
Copy link
Owner

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

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

Looks good - small thing.

My action items after that's fixed:

  • test locally with rviz plugin
  • merge
  • cherry pick to noetic / ROS2


// transform all the scans into the new global map coordinates
int id = 0;
bool processed = false;
Copy link
Owner

Choose a reason for hiding this comment

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

You don't use this variable. You can just ignore the return type if you're not checking its validity.

Copy link
Author

Choose a reason for hiding this comment

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

Hello, done.

And I am developing the lifelong merge, I am planning to add a new service something like "lifelong merge", it works as lifelong to decay old node when merge pose graph , if you want, I can create another PR after I finish.

@sunrentao
Copy link
Author

sunrentao commented Apr 15, 2020

Hello, we have a problem here, for example, if I use lifelong mode, after about 20 minutes , the map will drift, the dock position in the map frame will not be 100% same as initial map.

What is your opinion about this problem ? Thank you.

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.

None yet

2 participants