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

Add local SLAM result callback. #574

Merged

Conversation

ojura
Copy link
Contributor

@ojura ojura commented Oct 6, 2017

Depends on #619 (merged) and #617 (merged).
Related to #508.

Also, if cartographer_ros is going to use this, and we wish to serialize the saved range data, that will have to be handled in cartographer_ros, right?

@ojura ojura force-pushed the range-data-callback branch 3 times, most recently from dd1e25f to 548a537 Compare October 13, 2017 08:34
@ojura ojura force-pushed the range-data-callback branch 2 times, most recently from cbc22fb to b815d9f Compare October 16, 2017 11:45
@@ -186,7 +186,7 @@ LocalTrajectoryBuilder::AddAccumulatedRangeData(
{}, // 'low_resolution_point_cloud' is only used in 3D.
{}, // 'rotational_scan_matcher_histogram' is only used in 3D.
pose_estimate}),
std::move(insertion_submaps)});
std::move(insertion_submaps), gravity_aligned_range_data});
Copy link
Member

Choose a reason for hiding this comment

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

The idea was that there is no need for two ways to expose this data, i.e. that this replaces last_pose_estimate_. Wouldn't it make sense to push the scan_match_callback_ to the local trajectory builder and call it from here, i.e. no need to move the data out of local trajectory builder except through the call to the callback.

Copy link
Contributor Author

@ojura ojura Oct 16, 2017

Choose a reason for hiding this comment

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

As I mentioned in #508, my goal is to preserve the association of range data with the node ID (this was previously available because the range data was part of the trajectory node, and for my use case, I require that we know this association). We don't know the node ID yet in the local trajectory builder. I thought that returning the node ID from SPG::AddScan to the global trajectory builder was the most elegant solution.

Copy link
Member

Choose a reason for hiding this comment

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

I see. Then maybe keeping the last_pose_estimate_ and replacing it by the callback in the global trajectory builder is the way to go. Then we would not have a bool but rather an optional NodeId depending on whether a node was inserted?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

How would you make the NodeId optional? By using a smart pointer (unique)?

Copy link
Member

Choose a reason for hiding this comment

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

Yes, std::unique_ptr<> sounds good to me.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Updated.

@ojura ojura force-pushed the range-data-callback branch 2 times, most recently from 246fff9 to fd308f4 Compare October 19, 2017 19:19
: options_(options), thread_pool_(options.num_background_threads()) {
MapBuilder::MapBuilder(
const proto::MapBuilderOptions& options,
std::unique_ptr<InsertedRangeDataCallback> inserted_range_data_callback)
Copy link
Member

Choose a reason for hiding this comment

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

Why the unique_ptr? Seems unnecessary to me.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

The callback is optional, right? If you don't want to give one to libcartographer, you pass a null pointer during construction of MapBuilder.

GlobalTrajectoryBuilder(
const LocalTrajectoryBuilderOptions& options, const int trajectory_id,
SparsePoseGraph* const sparse_pose_graph,
InsertedRangeDataCallback* const inserted_range_data_callback)
Copy link
Member

Choose a reason for hiding this comment

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

Passing a pointer seems like premature optimization. Pass a copy?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Same as below - what if we did not provide a callback, which is covered by passing a null pointer?

Copy link
Member

Choose a reason for hiding this comment

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

You can also compare a std::function<> as a bool. It compares false if it is default constructed. if (the_function) { ... }.

@@ -43,6 +43,7 @@ class LocalTrajectoryBuilder {
struct InsertionResult {
std::shared_ptr<const mapping::TrajectoryNode::Data> constant_data;
std::vector<std::shared_ptr<const Submap>> insertion_submaps;
sensor::RangeData inserted_range_data;
Copy link
Member

Choose a reason for hiding this comment

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

This should not be added here. We want all the data from last_pose_estimate_ to be made available via the callback, even if there is not InsertionResult. This is redundant then. Moreover, we should then remove pose_estimate() from the global trajectory builder interface.

Copy link
Contributor Author

@ojura ojura Oct 20, 2017

Choose a reason for hiding this comment

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

Ooops. I completely forgot that I can't pass the range data if the insertion result was a null pointer. When I was thinking about the design, it made sense if the callback was only going to be called for inserted data.

Copy link
Contributor Author

@ojura ojura Oct 20, 2017

Choose a reason for hiding this comment

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

About the contents of pose_estimate: I want the original sensor::RangeData just like it was previously stored inside a trajectory node, not a transformed point cloud. Can I change the content of the PoseEstimate struct to reflect this?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

One additional thing: sometimes nullptr is returned because there isn't enough accumulated data. How will the global trajectory builder know not to invoke the callback, because last_pose_estimate_ hasn't been updated in the meantime and it would not make sense to invoke the callback with the same data? Maybe by comparing time from the PoseEstimate?

Copy link
Member

Choose a reason for hiding this comment

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

True. Maybe we should then get rid of the last_post_estimate_ completely and return this information instead, possible containing an insertion result, i.e. either nullptr, the MatchingResult not containing an InsertionResult, or the MatchingResult including an InsertionResult? Then it would also be clearer that these are results. pose_estimate() seems weird since it would only be called after adding some range data anyway.

Copy link
Contributor Author

@ojura ojura Oct 27, 2017

Choose a reason for hiding this comment

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

Okay, we can do that. I did not like that at first because it would not be following the way how the filtered range data is stored in the node constant data (not transformed to the local frame), and how the unfiltered data had also been stored there before.

Copy link
Member

Choose a reason for hiding this comment

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

As I said the important part is to be consistent across 2D and 3D. The other option is obviously to transform the 2D range data to be in tracking frame.

Copy link
Contributor Author

@ojura ojura Oct 27, 2017

Choose a reason for hiding this comment

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

This would correspond to gravity_aligned_range_data * pose_estimate_2d gravity_alignment.inverse() * pose_estimate_2d.inverse(), right?

range_data_in_local = Transform(gravity_aligned_range_data, pose_estimate_2d)

pose_estimate = pose_estimate_2d * gravity_alignment
pose_estimate.inverse() = 
    gravity_alignment_inverse() * pose_estimate_2d.inverse()

range_data_in_tracking = 
   Transform(range_data_in_local, pose_estimate.inverse()) = 
   Transform(gravity_aligned_range_data, 
      pose_estimate_2d * gravity_alignment.inverse() 
      * pose_estimate_2d.inverse())

And it would make sense to apply the same to filtered RangeData stored in node constant_data, right?

Pros for storing it in tracking frame: I think this would be a nicer design; range data is in the tracking frame, and the user can transform it to the local frame if they want, given the pose estimate of the tracking frame.
Cons: calculating the transform to the tracking frame is a bit wasteful. It would be faster to store it transformed to local frame, because that is actually used when inserting. It could be stored in a new variable (range_data_in_local?) which would then be used both for MatchingResult and passing to InsertIntoSubmap.

@wohe what do you think?

Copy link
Member

Choose a reason for hiding this comment

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

From your explanation it sounds you should keep it like it is. If there is not a good reason why something should be changed, we should not change it. This feels like bikeshedding otherwise.

Regarding the transform: Points get multiplied to the very right, not the left. Your last equality is wrong. pose_estimated_2d is from gravity-aligned to local map frame. gravity_alignment from tracking to gravity-aligned frame, so:

  1. gravity_aligned_range_data transformed by pose_estimate_2d is in local map frame.
  2. gravity_aligned_range_data transformed by gravity_alignment.inverse() is in tracking frame.

Also: Please do not change constant_data. It contains the data in the suitable format for loop closure detection and is furthermore completely unrelated to this PR.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Okay. I am going to introduce range_data_in_local, pass it to InsertIntoSubmap by const reference, and then move it into MatchingResult.

common::Time, const sensor::TimedRangeData& range_data);
void AddImuData(const sensor::ImuData& imu_data);
void AddOdometerData(const sensor::OdometryData& odometry_data);

private:
std::unique_ptr<InsertionResult> AddAccumulatedRangeData(
std::unique_ptr<MatchingResult> AddAccumulatedRangeData(
common::Time time, const sensor::RangeData& range_data);
sensor::RangeData TransformAndFilterRangeData(
const transform::Rigid3f& gravity_alignment,
const sensor::RangeData& range_data) const;
Copy link
Contributor Author

@ojura ojura Oct 25, 2017

Choose a reason for hiding this comment

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

A question. Why is this a const method? That does not make any sense to me.

Copy link
Member

Choose a reason for hiding this comment

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

Why not? It only uses this for the options and returns the sensor::RangeData. Seems good to me.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Sorry, I thought the const was for AddAccumulatedRangeData.

local_trajectory_builder_->AddRangeData(
node.time, sensor::TimedRangeData{
range_data.origin, range_data.returns, {}}));
if (matching_result != nullptr) {
Copy link
Contributor Author

Choose a reason for hiding this comment

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

This test now also performs the expect check for measurements eliminated by the motion filter (these previously had a nullptr for the insertion result and were not checked).

@ojura
Copy link
Contributor Author

ojura commented Oct 25, 2017

@wohe PTAL at the new implementation, and also at the comment which has been buried in a review above.

@ojura ojura force-pushed the range-data-callback branch from e559ea7 to 1e29f6f Compare October 25, 2017 19:55
@@ -40,10 +40,23 @@ namespace mapping_3d {
// without loop closure.
class LocalTrajectoryBuilder {
public:
// The following two structs are used for representing the result of adding
// range data in local SLAM (using 'LocalTrajectoryBuilder::AddRangeData()').
// A null pointer is returned for 'MatchingResult' in case if the range data
Copy link
Member

Choose a reason for hiding this comment

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

A null pointer -> 'nullptr'

common::Time, const sensor::TimedRangeData& range_data);
void AddImuData(const sensor::ImuData& imu_data);
void AddOdometerData(const sensor::OdometryData& odometry_data);

private:
std::unique_ptr<InsertionResult> AddAccumulatedRangeData(
std::unique_ptr<MatchingResult> AddAccumulatedRangeData(
common::Time time, const sensor::RangeData& range_data);
sensor::RangeData TransformAndFilterRangeData(
const transform::Rigid3f& gravity_alignment,
const sensor::RangeData& range_data) const;
Copy link
Member

Choose a reason for hiding this comment

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

Why not? It only uses this for the options and returns the sensor::RangeData. Seems good to me.

std::vector<std::shared_ptr<const Submap>> insertion_submaps;
};
struct MatchingResult {
std::shared_ptr<const sensor::RangeData> range_data;
Copy link
Member

Choose a reason for hiding this comment

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

Why the pointer? Seems unnecessary to me.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I wanted to ensure that unnecessary copying is avoided when transferring ownership of range_data to the library user. Although a unique pointer would be more appropriate since range_data is not used in rest of Cartographer, unlike constant_data. You think that we don't need pointers at all? I have always felt more comfortable when handling structures containing lots of data using pointers rather than relying on RVO or using move semantics.

Copy link
Member

Choose a reason for hiding this comment

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

Move semantics should achieve what you want. Otherwise: Do not optimize prematurely.

active_submaps_.InsertRangeData(
TransformRangeData(gravity_aligned_range_data,
transform::Embed3D(pose_estimate_2d.cast<float>())));

sensor::AdaptiveVoxelFilter adaptive_voxel_filter(
Copy link
Member

Choose a reason for hiding this comment

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

This seems unnecessary effort if the data is not inserted into the pose graph. Rather duplicate time/pose for performance and revert the change to the InsertionResult?

@@ -46,10 +46,6 @@ CollatedTrajectoryBuilder::CollatedTrajectoryBuilder(

CollatedTrajectoryBuilder::~CollatedTrajectoryBuilder() {}

const PoseEstimate& CollatedTrajectoryBuilder::pose_estimate() const {
Copy link
Member

Choose a reason for hiding this comment

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

This PR already is too large. Move the deletion of pose_estimate() to a follow up PR. This also allows us to change cartographer_ros without breaking it in between.

@ojura ojura force-pushed the range-data-callback branch 5 times, most recently from 06ab2d3 to a45b2e2 Compare October 27, 2017 12:24
@ojura
Copy link
Contributor Author

ojura commented Oct 27, 2017

Ok, I updated the PR with your suggestions, PTAL. Although that issue with gravity_alignment still exists; the current implementation still does not enable transforming the RangeData from MatchingResult using the local_posefrom MatchingResult in the same way for 2D and 3D, because you get the wrong result for 2D if you do not multiply the pose estimate with gravity_alignment.inverse().

@ojura ojura force-pushed the range-data-callback branch 2 times, most recently from 3ac22e2 to 1fb8789 Compare October 27, 2017 18:20
@ojura
Copy link
Contributor Author

ojura commented Oct 30, 2017

@wohe just a ping about whether we should pass to callback the range data in tracking or in local frame, as discussed above.

return;
}
sparse_pose_graph_->AddScan(insertion_result->constant_data, trajectory_id_,
insertion_result->insertion_submaps);
std::unique_ptr<mapping::NodeId> node_id = nullptr;
Copy link
Member

Choose a reason for hiding this comment

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

Remove the redundant nullptr since it does not help with readability?

@@ -58,6 +58,17 @@ class GlobalTrajectoryBuilderInterface {
virtual void AddSensorData(const sensor::OdometryData& odometry_data) = 0;
virtual void AddSensorData(
const sensor::FixedFramePoseData& fixed_frame_pose) = 0;

// An optional callback which is called when local SLAM finishes processing
Copy link
Member

Choose a reason for hiding this comment

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

Comments should be kept short and concise. There is the danger that when code changes in the future, comments go out of sync. How about this:

  // A callback which is called when local SLAM processed an accumulated
  // 'sensor::RangeData'. If the data was inserted into a submap,
  // reports the assigned 'NodeId', otherwise 'nullptr' if the data was filtered
  // out.

@@ -224,7 +226,7 @@ LocalTrajectoryBuilder::InsertIntoSubmap(
high_resolution_point_cloud,
low_resolution_point_cloud,
rotational_scan_matcher_histogram,
pose_observation}),
pose_estimate}),
Copy link
Member

Choose a reason for hiding this comment

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

For the future: Changes like these can easily be done in a separate PR. This one is already large enough.

@@ -195,13 +198,13 @@ const mapping::PoseEstimate& LocalTrajectoryBuilder::pose_estimate() const {

std::unique_ptr<LocalTrajectoryBuilder::InsertionResult>
LocalTrajectoryBuilder::InsertIntoSubmap(
const common::Time time, const sensor::RangeData& range_data_in_tracking,
const common::Time time, const sensor::RangeData& filtered_range_data,
Copy link
Member

Choose a reason for hiding this comment

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

Revert? That it is filtered seems unimportant to understand what this function does, but that it still has to be transformed is important.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I found it very unredable that the unfiltered variable in AddAccumulatedRangeData is also called range_data_in_tracking; and then filtered_range_data is passed again as range_data_in_tracking in InsertIntoSubmap. Maybe filtered_range_data_in_tracking?

Copy link
Member

Choose a reason for hiding this comment

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

I'm not feeling strongly about this. I personally would always chose conciseness if in doubt, but that is just me. That not every name is instantly understood by everyone is unavoidable. More of a question of how big the problem is here.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I think it's a subtle detail which should be made clearer, that filtered scans are inserted into submaps. If you don't mind, I'd like to keep it.

@@ -43,6 +43,7 @@ class LocalTrajectoryBuilder {
struct InsertionResult {
std::shared_ptr<const mapping::TrajectoryNode::Data> constant_data;
std::vector<std::shared_ptr<const Submap>> insertion_submaps;
sensor::RangeData inserted_range_data;
Copy link
Member

Choose a reason for hiding this comment

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

From your explanation it sounds you should keep it like it is. If there is not a good reason why something should be changed, we should not change it. This feels like bikeshedding otherwise.

Regarding the transform: Points get multiplied to the very right, not the left. Your last equality is wrong. pose_estimated_2d is from gravity-aligned to local map frame. gravity_alignment from tracking to gravity-aligned frame, so:

  1. gravity_aligned_range_data transformed by pose_estimate_2d is in local map frame.
  2. gravity_aligned_range_data transformed by gravity_alignment.inverse() is in tracking frame.

Also: Please do not change constant_data. It contains the data in the suitable format for loop closure detection and is furthermore completely unrelated to this PR.

std::function<void(int /* trajectory ID */, common::Time,
transform::Rigid3d /* local pose estimate */,
sensor::RangeData /* in local frame */,
std::unique_ptr<const mapping::NodeId>)>;
Copy link

Choose a reason for hiding this comment

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

@ojura @wohe I am currently working on the design for cloud-based SLAM and for that I need to forward all the information necessary to formulate the global SLAM problem in the cloud. Part of that is the InsertionResult. So I am wondering whether we can extend this callback to also include the InsertionResult.

Copy link
Contributor Author

@ojura ojura Nov 10, 2017

Choose a reason for hiding this comment

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

Sure, why not. Perhaps the node_id could be filled inside the insertion result by the global trajectory builder?

Copy link

Choose a reason for hiding this comment

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

e.g.

std::function<void(int /* trajectory ID */, MatchingResult)>

Copy link

Choose a reason for hiding this comment

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

Let's see what Wolfgang thinks. I realize I am somewhat late to the party :)

Copy link
Contributor Author

Choose a reason for hiding this comment

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

No, you're just in time :) Fell free to submit a PR over at larics/cartographer for the range-data-callback branch.

Copy link
Contributor Author

@ojura ojura Nov 11, 2017

Choose a reason for hiding this comment

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

@cschuet On the other hand, there doesn't exist a single MatchingResult (or InsertionResult) class. There are two separate ones, one for 2D and one for 3D local trajectory builder. GlobalTrajectoryBuilder is templated. Perhaps changing that belongs in another Cartographer PR.

wally-the-cartographer pushed a commit that referenced this pull request Nov 10, 2017
)

In preparation for #574. Depends on ~~#618~~ (merged) and ~~#617~~ (merged).
@ojura ojura force-pushed the range-data-callback branch from 1944735 to 800196f Compare November 10, 2017 13:52
@cschuet
Copy link

cschuet commented Nov 11, 2017 via email

@ojura ojura force-pushed the range-data-callback branch from fccc9d7 to ef32f42 Compare November 14, 2017 14:47
Copy link
Member

@wohe wohe left a comment

Choose a reason for hiding this comment

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

Let's discuss the naming of the callback. Other than that it looks good to me.

// A callback which is called after local SLAM processes an accumulated
// 'sensor::RangeData'. If the data was inserted into a submap, reports the
// assigned 'NodeId', otherwise 'nullptr' if the data was filtered out.
using AccumulatedRangeDataCallback =
Copy link
Member

Choose a reason for hiding this comment

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

The range data is only part of what this callback gets as information. LocalSlamResultCallback or LocalSlamCallback maybe? This would also better match your comment. @cschuet Opinion?

Copy link

Choose a reason for hiding this comment

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

I would prefer LocalSlamResultCallback but both are fine for me.

Copy link
Contributor Author

@ojura ojura Nov 14, 2017

Choose a reason for hiding this comment

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

The "range data" in the callback name refers not only to the contained range data that is passed to the callback, but to the fact that the callback has been called right after this data has been processed (the callback is called from AddRangefinderData() after all). The callback is not called after e.g. adding IMU or odometry data, so I thought this name would emphasize this timing.

But the question is - is that important? The user probably just cares about the pose estimate the most, and probably does not care about the fact that it is updated only after range data is added - it's an internal libcartographer detail. In that case I agree with both of your suggestions.

On the other hand, if we do want to hint that this is closely related to processing range data, I suggest we go something with "range data" in the name. Either way is good to me.

Copy link
Member

Choose a reason for hiding this comment

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

Let's call it LocalSlamResultCallback then.

@ojura
Copy link
Contributor Author

ojura commented Nov 14, 2017

@wohe Renamed.

Copy link
Member

@wohe wohe left a comment

Choose a reason for hiding this comment

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

One last nit.

using AccumulatedRangeDataCallback =
mapping::GlobalTrajectoryBuilderInterface::AccumulatedRangeDataCallback;
using LocalSlamResultCallback =
mapping::GlobalTrajectoryBuilderInterface::LocalSlamResultCallback;
Copy link
Member

Choose a reason for hiding this comment

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

Can't we drop the mapping:: prefix?

@ojura
Copy link
Contributor Author

ojura commented Nov 14, 2017

Updated

@wohe
Copy link
Member

wohe commented Nov 14, 2017

@wally-the-cartographer merge

@wally-the-cartographer
Copy link
Collaborator

Merge requested by authorized user wohe. Merge queue now has a length of 2.

@ojura ojura changed the title Add inserted range data callback Add local SLAM result callback. Nov 14, 2017
@SirVer SirVer force-pushed the range-data-callback branch from 4fcba93 to 77586c2 Compare November 14, 2017 15:53
@wally-the-cartographer wally-the-cartographer merged commit 818e5e1 into cartographer-project:master Nov 14, 2017
@ojura ojura deleted the range-data-callback branch November 14, 2017 16:23
wohe added a commit to wohe/cartographer_ros that referenced this pull request Nov 14, 2017
wally-the-cartographer pushed a commit to cartographer-project/cartographer_ros that referenced this pull request Nov 14, 2017
ojura pushed a commit to larics/cartographer_combined that referenced this pull request Nov 14, 2017
wally-the-cartographer pushed a commit to cartographer-project/cartographer_ros that referenced this pull request Nov 16, 2017
Replaces #556.
Use `LocalSlamResultCallback` cartographer-project/cartographer#574 instead of `PoseEstimate`.
ojura added a commit to larics/cartographer_combined that referenced this pull request Nov 16, 2017
ojura added a commit to larics/cartographer that referenced this pull request Jan 22, 2018
…artographer-project#574)

This reverts commit 125aee3.

This got fixed upstream, so perception_pcl (ros-perception/perception_pcl@8b32dcd) did remove this hack too.
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.

6 participants