ConstantData is now owned by the SPG. (#326)
parent
1d256adeb5
commit
5294050f51
|
@ -26,7 +26,7 @@ namespace cartographer_ros {
|
||||||
MapBuilderBridge::MapBuilderBridge(const NodeOptions& options,
|
MapBuilderBridge::MapBuilderBridge(const NodeOptions& options,
|
||||||
tf2_ros::Buffer* const tf_buffer)
|
tf2_ros::Buffer* const tf_buffer)
|
||||||
: options_(options),
|
: options_(options),
|
||||||
map_builder_(options.map_builder_options, &constant_data_),
|
map_builder_(options.map_builder_options),
|
||||||
tf_buffer_(tf_buffer) {}
|
tf_buffer_(tf_buffer) {}
|
||||||
|
|
||||||
int MapBuilderBridge::AddTrajectory(
|
int MapBuilderBridge::AddTrajectory(
|
||||||
|
|
|
@ -64,8 +64,6 @@ class MapBuilderBridge {
|
||||||
private:
|
private:
|
||||||
const NodeOptions options_;
|
const NodeOptions options_;
|
||||||
|
|
||||||
std::deque<cartographer::mapping::TrajectoryNode::ConstantData>
|
|
||||||
constant_data_;
|
|
||||||
cartographer::mapping::MapBuilder map_builder_;
|
cartographer::mapping::MapBuilder map_builder_;
|
||||||
tf2_ros::Buffer* const tf_buffer_;
|
tf2_ros::Buffer* const tf_buffer_;
|
||||||
std::unordered_map<int, std::unique_ptr<SensorBridge>> sensor_bridges_;
|
std::unordered_map<int, std::unique_ptr<SensorBridge>> sensor_bridges_;
|
||||||
|
|
Loading…
Reference in New Issue