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

Don't run final optimization in visualize_pbstream.launch #1157

Merged
merged 3 commits into from
Jan 16, 2019

Conversation

MichaelGrupp
Copy link
Contributor

Replaces the offline node with the normal node.

The problem is that the offline node immediately runs a final
optimization with visualize_pbstream.lua, which is most likely not the
configuration that was used to generate the pbstream. This can lead to
effects like distortions in the map e.g. due to different weights, even
though the actual saved state is fine.

Replaces the offline node with the normal node.

The problem is that the offline node immediately runs a final
optimization with `visualize_pbstream.lua`, which is most likely not the
configuration that was used to generate the pbstream. This can lead to
effects like distortions in the map e.g. due to different weights, even
though the actual saved state is fine.
@MichaelGrupp
Copy link
Contributor Author

You only get a warning now that there are no input topics, but this can safely ignored.

Note: I think I already tried this and it didn't work a few months ago before #1089 was merged, because back then the node couldn't finish trajectories that were just waiting for their topics. But now the node terminates cleanly ;)

@ojura
Copy link
Contributor

ojura commented Jan 14, 2019

If you do not intend to optimize the loaded trajectory, why not freeze it instead?

@MichaelGrupp
Copy link
Contributor Author

If you do not intend to optimize the loaded trajectory, why not freeze it?

Then the constraints wouldn't be displayed.

@ojura
Copy link
Contributor

ojura commented Jan 14, 2019

Hmm, I see. I still feel loading an unfrozen trajectory for this purpose is not a robust solution, because the moment it gets optimized, it will get screwed up. I see two things which would both help to solve this robustly.

The first would be to indeed load it frozen. Not loading the constraints for frozen trajectories is a memory saving-optimization, and perhaps deserves an option to disable it.

The second would be to able to ensure the same pose graph options are loaded. I actually implemented this in a private branch and it works well; if there's interest, we can look into upstreaming it. The idea is that the complete node options (including the map builder options) are stored in the .pbstream header, like I envisioned in this rfc from some time ago. You would then be able to tell Cartographer to use the node configuration from the .pbstream header instead of a new configuration_basename.

@MichaelGrupp
Copy link
Contributor Author

MichaelGrupp commented Jan 14, 2019

the moment it gets optimized, it will get screwed up

Yes, however: when would that happen? Unless there's sensor input it just does nothing. The only scenario I could think of is that you have a sensor publisher publishing the expected topics in parallel and the "visualization node" starts SLAMing, but this can be blocked by dropping all sensor data of the parent config backpack_2d.lua (see my last commit).

Not loading the constraints for frozen trajectories is a memory saving-optimization, and perhaps deserves an option to disable it.

Unless there's another benefit I wouldn't want to change API only for this simple visualization tool...

You would then be able to tell Cartographer to use the node configuration from the .pbstream header instead of a new configuration_basename.

This sounds useful, regardless of this PR.

@ojura
Copy link
Contributor

ojura commented Jan 14, 2019

With the online node, instead of setting the sampler ratios to zero, I think it would make more sense just not to start the default trajectory. This is controlled by the flag start_trajectory_with_default_topics.

@MichaelGrupp
Copy link
Contributor Author

Thanks, I forgot about this option. Then it also doesn't warn about waiting for topics.

@MichaelGrupp
Copy link
Contributor Author

@gaschler merge?

@gaschler gaschler merged commit 0d65d13 into cartographer-project:master Jan 16, 2019
@MichaelGrupp MichaelGrupp deleted the vispbstream-patch branch January 16, 2019 11:48
@ojura
Copy link
Contributor

ojura commented Jan 17, 2019

Related to my previous comment: cartographer-project/rfcs#38

qh-huang pushed a commit to qh-huang/cartographer_ros that referenced this pull request May 21, 2019
…er-project#1157)

* Don't run final optimization in visualize_pbstream.launch

Replaces the offline node with the normal node.

The problem is that the offline node immediately runs a final
optimization with `visualize_pbstream.lua`, which is most likely not the
configuration that was used to generate the pbstream. This can lead to
effects like distortions in the map e.g. due to different weights, even
though the actual saved state is fine.

* Drop all /echoes or /imu messages.

* Use -start_trajectory_with_default_topics=false
akshay-prsd pushed a commit to BossaNova/cartographer_ros that referenced this pull request Jul 15, 2019
…er-project#1157)

* Don't run final optimization in visualize_pbstream.launch

Replaces the offline node with the normal node.

The problem is that the offline node immediately runs a final
optimization with `visualize_pbstream.lua`, which is most likely not the
configuration that was used to generate the pbstream. This can lead to
effects like distortions in the map e.g. due to different weights, even
though the actual saved state is fine.

* Drop all /echoes or /imu messages.

* Use -start_trajectory_with_default_topics=false
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants