NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
state_parameters.h
Go to the documentation of this file.
1 /* Copyright (c) 2017, United States Government, as represented by the
2  * Administrator of the National Aeronautics and Space Administration.
3  *
4  * All rights reserved.
5  *
6  * The Astrobee platform is licensed under the Apache License, Version 2.0
7  * (the "License"); you may not use this file except in compliance with the
8  * License. You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15  * License for the specific language governing permissions and limitations
16  * under the License.
17  */
18 #ifndef CALIBRATION_STATE_PARAMETERS_H_
19 #define CALIBRATION_STATE_PARAMETERS_H_
20 
24 
25 #include <Eigen/Core>
26 #include <Eigen/Geometry>
27 
28 #include <vector>
29 
30 namespace calibration {
32  void Print() {
33  LogInfo("Focal lengths: " << std::endl << focal_lengths.matrix());
34  LogInfo("Principal points: " << std::endl << principal_points.matrix());
35  LogInfo("Distortion: " << std::endl << distortion.matrix());
36  }
37 
38  Eigen::Vector2d focal_lengths;
39  Eigen::Vector2d principal_points;
40  Eigen::VectorXd distortion;
41 };
42 
43 // Container for state parameters in vector form used during optimization
45  void SetInitialStateParameters(const StateParameters& initial_state_parameters) {
46  focal_lengths = initial_state_parameters.focal_lengths;
47  principal_points = initial_state_parameters.principal_points;
48  distortion = initial_state_parameters.distortion;
49  }
50 
51  void AddCameraTTarget(const Eigen::Isometry3d& camera_T_target) {
52  camera_T_targets.emplace_back(optimization_common::VectorFromIsometry3d(camera_T_target));
53  }
54 
56  StateParameters optimized_state_parameters;
57  optimized_state_parameters.focal_lengths = focal_lengths;
58  optimized_state_parameters.principal_points = principal_points;
59  optimized_state_parameters.distortion = distortion;
60  return optimized_state_parameters;
61  }
62 
63  std::vector<Eigen::Isometry3d> OptimizedCameraTTargets() const {
64  std::vector<Eigen::Isometry3d> optimized_camera_T_targets;
65  for (const auto& camera_T_target : camera_T_targets)
66  optimized_camera_T_targets.emplace_back(optimization_common::Isometry3d(camera_T_target));
67  return optimized_camera_T_targets;
68  }
69 
70  Eigen::Vector2d focal_lengths;
71  Eigen::Vector2d principal_points;
72  Eigen::VectorXd distortion;
73  std::vector<Eigen::Matrix<double, 6, 1>> camera_T_targets;
74 };
75 
77  void Print() {
78  LogInfo("Focal length covariances: " << std::endl << focal_lengths.matrix());
79  LogInfo("Principal point covariances: " << std::endl << principal_points.matrix());
80  LogInfo("Distortion covariances: " << std::endl << distortion.matrix());
81  }
82 
83  Eigen::Matrix2d focal_lengths;
84  Eigen::Matrix2d principal_points;
85  Eigen::MatrixXd distortion;
86 };
87 } // namespace calibration
88 
89 #endif // CALIBRATION_STATE_PARAMETERS_H_
optimization_common::Isometry3d
Eigen::Isometry3d Isometry3d(const Eigen::Matrix< double, 6, 1 > &isometry_vector)
Definition: utilities.cc:39
LogInfo
#define LogInfo(msg)
Definition: logger.h:41
calibration::StateParametersCovariances
Definition: state_parameters.h:76
calibration::StateParameters::principal_points
Eigen::Vector2d principal_points
Definition: state_parameters.h:39
logger.h
calibration::StateParametersCovariances::distortion
Eigen::MatrixXd distortion
Definition: state_parameters.h:85
calibration::StateParameters::Print
void Print()
Definition: state_parameters.h:32
calibration::StateParameters::focal_lengths
Eigen::Vector2d focal_lengths
Definition: state_parameters.h:38
calibration::OptimizationStateParameters::distortion
Eigen::VectorXd distortion
Definition: state_parameters.h:72
localization_common::Isometry3d
Eigen::Isometry3d Isometry3d(const Eigen::Vector3d &translation, const RotationType &rotation)
Definition: utilities.h:226
calibration::OptimizationStateParameters::camera_T_targets
std::vector< Eigen::Matrix< double, 6, 1 > > camera_T_targets
Definition: state_parameters.h:73
optimization_common::VectorFromIsometry3d
Eigen::Matrix< double, 6, 1 > VectorFromIsometry3d(const Eigen::Isometry3d &isometry_3d)
Definition: utilities.cc:22
calibration::StateParameters
Definition: state_parameters.h:31
calibration::OptimizationStateParameters::OptimizedCameraTTargets
std::vector< Eigen::Isometry3d > OptimizedCameraTTargets() const
Definition: state_parameters.h:63
utilities.h
calibration::OptimizationStateParameters::AddCameraTTarget
void AddCameraTTarget(const Eigen::Isometry3d &camera_T_target)
Definition: state_parameters.h:51
calibration::StateParametersCovariances::focal_lengths
Eigen::Matrix2d focal_lengths
Definition: state_parameters.h:83
calibration::StateParametersCovariances::principal_points
Eigen::Matrix2d principal_points
Definition: state_parameters.h:84
eigen_vectors.h
calibration::StateParametersCovariances::Print
void Print()
Definition: state_parameters.h:77
calibration::OptimizationStateParameters::focal_lengths
Eigen::Vector2d focal_lengths
Definition: state_parameters.h:70
calibration::OptimizationStateParameters::SetInitialStateParameters
void SetInitialStateParameters(const StateParameters &initial_state_parameters)
Definition: state_parameters.h:45
calibration::OptimizationStateParameters::principal_points
Eigen::Vector2d principal_points
Definition: state_parameters.h:71
calibration
Definition: camera_target_based_intrinsics_calibrator.h:42
calibration::OptimizationStateParameters
Definition: state_parameters.h:44
calibration::StateParameters::distortion
Eigen::VectorXd distortion
Definition: state_parameters.h:40
calibration::OptimizationStateParameters::OptimizedStateParameters
StateParameters OptimizedStateParameters() const
Definition: state_parameters.h:55