diff --git a/CMakeLists.txt b/CMakeLists.txt index bc4724d..ad66a17 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -cmake_minimum_required (VERSION 2.8.7) +cmake_minimum_required (VERSION 2.8.12) project(cartographer) set(CARTOGRAPHER_MAJOR_VERSION 1) diff --git a/cartographer/mapping_3d/ceres_pose.cc b/cartographer/mapping_3d/ceres_pose.cc index 2ca7f83..b1d940f 100644 --- a/cartographer/mapping_3d/ceres_pose.cc +++ b/cartographer/mapping_3d/ceres_pose.cc @@ -21,13 +21,15 @@ namespace mapping_3d { CeresPose::CeresPose( const transform::Rigid3d& rigid, + std::unique_ptr translation_parametrization, std::unique_ptr rotation_parametrization, ceres::Problem* problem) : translation_({{rigid.translation().x(), rigid.translation().y(), rigid.translation().z()}}), rotation_({{rigid.rotation().w(), rigid.rotation().x(), rigid.rotation().y(), rigid.rotation().z()}}) { - problem->AddParameterBlock(translation_.data(), 3); + problem->AddParameterBlock(translation_.data(), 3, + translation_parametrization.release()); problem->AddParameterBlock(rotation_.data(), 4, rotation_parametrization.release()); } diff --git a/cartographer/mapping_3d/ceres_pose.h b/cartographer/mapping_3d/ceres_pose.h index 2976128..7dd29bb 100644 --- a/cartographer/mapping_3d/ceres_pose.h +++ b/cartographer/mapping_3d/ceres_pose.h @@ -31,6 +31,7 @@ class CeresPose { public: CeresPose( const transform::Rigid3d& rigid, + std::unique_ptr translation_parametrization, std::unique_ptr rotation_parametrization, ceres::Problem* problem); diff --git a/cartographer/mapping_3d/scan_matching/ceres_scan_matcher.cc b/cartographer/mapping_3d/scan_matching/ceres_scan_matcher.cc index 10148d4..41ce5cd 100644 --- a/cartographer/mapping_3d/scan_matching/ceres_scan_matcher.cc +++ b/cartographer/mapping_3d/scan_matching/ceres_scan_matcher.cc @@ -94,7 +94,7 @@ void CeresScanMatcher::Match(const transform::Rigid3d& previous_pose, ceres::Solver::Summary* const summary) { ceres::Problem problem; CeresPose ceres_pose( - initial_pose_estimate, + initial_pose_estimate, nullptr /* translation_parameterization */, options_.only_optimize_yaw() ? std::unique_ptr( common::make_unique* constant_node_data) : options_(options), - optimization_problem_(options_.optimization_problem_options()), + optimization_problem_(options_.optimization_problem_options(), + sparse_pose_graph::OptimizationProblem::FixZ::kNo), constraint_builder_(options_.constraint_builder_options(), thread_pool), constant_node_data_(constant_node_data) {} diff --git a/cartographer/mapping_3d/sparse_pose_graph/optimization_problem.cc b/cartographer/mapping_3d/sparse_pose_graph/optimization_problem.cc index 5519fcc..2f003c2 100644 --- a/cartographer/mapping_3d/sparse_pose_graph/optimization_problem.cc +++ b/cartographer/mapping_3d/sparse_pose_graph/optimization_problem.cc @@ -72,8 +72,9 @@ struct ConstantYawQuaternionPlus { OptimizationProblem::OptimizationProblem( const mapping::sparse_pose_graph::proto::OptimizationProblemOptions& - options) - : options_(options) {} + options, + FixZ fix_z) + : options_(options), fix_z_(fix_z) {} OptimizationProblem::~OptimizationProblem() {} @@ -114,13 +115,21 @@ void OptimizationProblem::Solve( ceres::Problem::Options problem_options; ceres::Problem problem(problem_options); + const auto translation_parameterization = + [this]() -> std::unique_ptr { + return fix_z_ == FixZ::kYes + ? common::make_unique( + 3, std::vector{2}) + : nullptr; + }; + // Set the starting point. std::deque C_submaps; std::deque C_point_clouds; // Tie the first submap to the origin. CHECK(!submap_transforms->empty()); C_submaps.emplace_back( - transform::Rigid3d::Identity(), + transform::Rigid3d::Identity(), translation_parameterization(), common::make_unique>(), &problem); @@ -128,12 +137,12 @@ void OptimizationProblem::Solve( for (size_t i = 1; i != submap_transforms->size(); ++i) { C_submaps.emplace_back( - (*submap_transforms)[i], + (*submap_transforms)[i], translation_parameterization(), common::make_unique(), &problem); } for (size_t j = 0; j != node_data_.size(); ++j) { C_point_clouds.emplace_back( - node_data_[j].point_cloud_pose, + node_data_[j].point_cloud_pose, translation_parameterization(), common::make_unique(), &problem); } diff --git a/cartographer/mapping_3d/sparse_pose_graph/optimization_problem.h b/cartographer/mapping_3d/sparse_pose_graph/optimization_problem.h index 4625b49..84cd6db 100644 --- a/cartographer/mapping_3d/sparse_pose_graph/optimization_problem.h +++ b/cartographer/mapping_3d/sparse_pose_graph/optimization_problem.h @@ -47,9 +47,12 @@ class OptimizationProblem { public: using Constraint = mapping::SparsePoseGraph::Constraint; - explicit OptimizationProblem( + enum class FixZ { kYes, kNo }; + + OptimizationProblem( const mapping::sparse_pose_graph::proto::OptimizationProblemOptions& - options); + options, + FixZ fix_z); ~OptimizationProblem(); OptimizationProblem(const OptimizationProblem&) = delete; @@ -72,6 +75,7 @@ class OptimizationProblem { private: mapping::sparse_pose_graph::proto::OptimizationProblemOptions options_; + FixZ fix_z_; std::map> imu_data_; std::vector node_data_; double gravity_constant_ = 9.8; diff --git a/cartographer/mapping_3d/sparse_pose_graph/optimization_problem_test.cc b/cartographer/mapping_3d/sparse_pose_graph/optimization_problem_test.cc index 05afc9c..a17f3e8 100644 --- a/cartographer/mapping_3d/sparse_pose_graph/optimization_problem_test.cc +++ b/cartographer/mapping_3d/sparse_pose_graph/optimization_problem_test.cc @@ -34,7 +34,8 @@ namespace { class OptimizationProblemTest : public ::testing::Test { protected: OptimizationProblemTest() - : optimization_problem_(CreateOptions()), rng_(45387) {} + : optimization_problem_(CreateOptions(), OptimizationProblem::FixZ::kNo), + rng_(45387) {} mapping::sparse_pose_graph::proto::OptimizationProblemOptions CreateOptions() { diff --git a/cartographer/sensor/ordered_multi_queue.cc b/cartographer/sensor/ordered_multi_queue.cc index fc0a28b..58c2d19 100644 --- a/cartographer/sensor/ordered_multi_queue.cc +++ b/cartographer/sensor/ordered_multi_queue.cc @@ -48,7 +48,7 @@ OrderedMultiQueue::~OrderedMultiQueue() { void OrderedMultiQueue::AddQueue(const QueueKey& queue_key, Callback callback) { CHECK_EQ(queues_.count(queue_key), 0); - queues_[queue_key].callback = callback; + queues_[queue_key].callback = std::move(callback); } void OrderedMultiQueue::MarkQueueAsFinished(const QueueKey& queue_key) {