Move cerec_pose.* to mapping/pose_graph. (#874)

master
Alexander Belyaev 2018-02-01 15:16:50 +01:00 committed by GitHub
parent 731bc89f22
commit 8ea46857ac
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
4 changed files with 17 additions and 12 deletions

View File

@ -14,10 +14,11 @@
* limitations under the License. * limitations under the License.
*/ */
#include "cartographer/mapping_3d/ceres_pose.h" #include "cartographer/mapping/pose_graph/ceres_pose.h"
namespace cartographer { namespace cartographer {
namespace mapping_3d { namespace mapping {
namespace pose_graph {
CeresPose::CeresPose( CeresPose::CeresPose(
const transform::Rigid3d& rigid, const transform::Rigid3d& rigid,
@ -42,5 +43,6 @@ const transform::Rigid3d CeresPose::ToRigid() const {
Eigen::Quaterniond(rotation[0], rotation[1], rotation[2], rotation[3])); Eigen::Quaterniond(rotation[0], rotation[1], rotation[2], rotation[3]));
} }
} // namespace mapping_3d } // namespace pose_graph
} // namespace mapping
} // namespace cartographer } // namespace cartographer

View File

@ -14,8 +14,8 @@
* limitations under the License. * limitations under the License.
*/ */
#ifndef CARTOGRAPHER_MAPPING_3D_CERES_POSE_H_ #ifndef CARTOGRAPHER_MAPPING_POSE_GRAPH_CERES_POSE_H_
#define CARTOGRAPHER_MAPPING_3D_CERES_POSE_H_ #define CARTOGRAPHER_MAPPING_POSE_GRAPH_CERES_POSE_H_
#include <array> #include <array>
#include <memory> #include <memory>
@ -25,7 +25,8 @@
#include "ceres/ceres.h" #include "ceres/ceres.h"
namespace cartographer { namespace cartographer {
namespace mapping_3d { namespace mapping {
namespace pose_graph {
class CeresPose { class CeresPose {
public: public:
@ -49,7 +50,8 @@ class CeresPose {
std::shared_ptr<Data> data_; std::shared_ptr<Data> data_;
}; };
} // namespace mapping_3d } // namespace pose_graph
} // namespace mapping
} // namespace cartographer } // namespace cartographer
#endif // CARTOGRAPHER_MAPPING_3D_CERES_POSE_H_ #endif // CARTOGRAPHER_MAPPING_POSE_GRAPH_CERES_POSE_H_

View File

@ -32,7 +32,7 @@
#include "cartographer/common/time.h" #include "cartographer/common/time.h"
#include "cartographer/internal/mapping_3d/acceleration_cost_function.h" #include "cartographer/internal/mapping_3d/acceleration_cost_function.h"
#include "cartographer/internal/mapping_3d/rotation_cost_function.h" #include "cartographer/internal/mapping_3d/rotation_cost_function.h"
#include "cartographer/mapping_3d/ceres_pose.h" #include "cartographer/mapping/pose_graph/ceres_pose.h"
#include "cartographer/mapping_3d/imu_integration.h" #include "cartographer/mapping_3d/imu_integration.h"
#include "cartographer/mapping_3d/pose_graph/spa_cost_function.h" #include "cartographer/mapping_3d/pose_graph/spa_cost_function.h"
#include "cartographer/mapping_3d/rotation_parameterization.h" #include "cartographer/mapping_3d/rotation_parameterization.h"
@ -46,9 +46,10 @@
namespace cartographer { namespace cartographer {
namespace mapping_3d { namespace mapping_3d {
namespace pose_graph { namespace pose_graph {
namespace { namespace {
using ::cartographer::mapping::pose_graph::CeresPose;
// For odometry. // For odometry.
std::unique_ptr<transform::Rigid3d> Interpolate( std::unique_ptr<transform::Rigid3d> Interpolate(
const sensor::MapByTime<sensor::OdometryData>& map_by_time, const sensor::MapByTime<sensor::OdometryData>& map_by_time,

View File

@ -23,7 +23,7 @@
#include "cartographer/common/ceres_solver_options.h" #include "cartographer/common/ceres_solver_options.h"
#include "cartographer/common/make_unique.h" #include "cartographer/common/make_unique.h"
#include "cartographer/internal/mapping_3d/scan_matching/occupied_space_cost_function.h" #include "cartographer/internal/mapping_3d/scan_matching/occupied_space_cost_function.h"
#include "cartographer/mapping_3d/ceres_pose.h" #include "cartographer/mapping/pose_graph/ceres_pose.h"
#include "cartographer/mapping_3d/rotation_parameterization.h" #include "cartographer/mapping_3d/rotation_parameterization.h"
#include "cartographer/mapping_3d/scan_matching/rotation_delta_cost_functor.h" #include "cartographer/mapping_3d/scan_matching/rotation_delta_cost_functor.h"
#include "cartographer/mapping_3d/scan_matching/translation_delta_cost_functor.h" #include "cartographer/mapping_3d/scan_matching/translation_delta_cost_functor.h"
@ -75,7 +75,7 @@ void CeresScanMatcher::Match(const Eigen::Vector3d& target_translation,
transform::Rigid3d* const pose_estimate, transform::Rigid3d* const pose_estimate,
ceres::Solver::Summary* const summary) { ceres::Solver::Summary* const summary) {
ceres::Problem problem; ceres::Problem problem;
CeresPose ceres_pose( mapping::pose_graph::CeresPose ceres_pose(
initial_pose_estimate, nullptr /* translation_parameterization */, initial_pose_estimate, nullptr /* translation_parameterization */,
options_.only_optimize_yaw() options_.only_optimize_yaw()
? std::unique_ptr<ceres::LocalParameterization>( ? std::unique_ptr<ceres::LocalParameterization>(