Open3D (C++ API)  0.17.0
RGBDOdometryJacobian.h
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // - Open3D: www.open3d.org -
3 // ----------------------------------------------------------------------------
4 // Copyright (c) 2018-2023 www.open3d.org
5 // SPDX-License-Identifier: MIT
6 // ----------------------------------------------------------------------------
7 
8 #pragma once
9 
10 #include <Eigen/Core>
11 #include <iostream>
12 #include <tuple>
13 #include <vector>
14 
16 #include "open3d/utility/Eigen.h"
17 
18 namespace open3d {
19 
20 namespace geometry {
21 class Image;
22 }
23 
24 namespace geometry {
25 class RGBDImage;
26 }
27 
28 namespace pipelines {
29 namespace odometry {
30 
31 typedef std::vector<Eigen::Vector4i, utility::Vector4i_allocator>
33 
38 public:
41  virtual ~RGBDOdometryJacobian() {}
42 
43 public:
49  int row,
50  std::vector<Eigen::Vector6d, utility::Vector6d_allocator> &J_r,
51  std::vector<double> &r,
52  std::vector<double> &w,
53  const geometry::RGBDImage &source,
54  const geometry::RGBDImage &target,
55  const geometry::Image &source_xyz,
56  const geometry::RGBDImage &target_dx,
57  const geometry::RGBDImage &target_dy,
58  const Eigen::Matrix3d &intrinsic,
59  const Eigen::Matrix4d &extrinsic,
60  const CorrespondenceSetPixelWise &corresps) const = 0;
61 };
62 
73 public:
77 
78 public:
81  int row,
82  std::vector<Eigen::Vector6d, utility::Vector6d_allocator> &J_r,
83  std::vector<double> &r,
84  std::vector<double> &w,
85  const geometry::RGBDImage &source,
86  const geometry::RGBDImage &target,
87  const geometry::Image &source_xyz,
88  const geometry::RGBDImage &target_dx,
89  const geometry::RGBDImage &target_dy,
90  const Eigen::Matrix3d &intrinsic,
91  const Eigen::Matrix4d &extrinsic,
92  const CorrespondenceSetPixelWise &corresps) const override;
93 };
94 
109 public:
113 
114 public:
117  int row,
118  std::vector<Eigen::Vector6d, utility::Vector6d_allocator> &J_r,
119  std::vector<double> &r,
120  std::vector<double> &w,
121  const geometry::RGBDImage &source,
122  const geometry::RGBDImage &target,
123  const geometry::Image &source_xyz,
124  const geometry::RGBDImage &target_dx,
125  const geometry::RGBDImage &target_dy,
126  const Eigen::Matrix3d &intrinsic,
127  const Eigen::Matrix4d &extrinsic,
128  const CorrespondenceSetPixelWise &corresps) const override;
129 };
130 
131 } // namespace odometry
132 } // namespace pipelines
133 } // namespace open3d
The Image class stores image with customizable width, height, num of channels and bytes per channel.
Definition: Image.h:34
RGBDImage is for a pair of registered color and depth images,.
Definition: RGBDImage.h:27
Class to compute Jacobian using color term.
Definition: RGBDOdometryJacobian.h:72
void ComputeJacobianAndResidual(int row, std::vector< Eigen::Vector6d, utility::Vector6d_allocator > &J_r, std::vector< double > &r, std::vector< double > &w, const geometry::RGBDImage &source, const geometry::RGBDImage &target, const geometry::Image &source_xyz, const geometry::RGBDImage &target_dx, const geometry::RGBDImage &target_dy, const Eigen::Matrix3d &intrinsic, const Eigen::Matrix4d &extrinsic, const CorrespondenceSetPixelWise &corresps) const override
Parameterized Constructor.
Definition: RGBDOdometryJacobian.cpp:25
RGBDOdometryJacobianFromColorTerm()
Default Constructor.
Definition: RGBDOdometryJacobian.h:75
~RGBDOdometryJacobianFromColorTerm() override
Definition: RGBDOdometryJacobian.h:76
Class to compute Jacobian using hybrid term.
Definition: RGBDOdometryJacobian.h:108
~RGBDOdometryJacobianFromHybridTerm() override
Definition: RGBDOdometryJacobian.h:112
RGBDOdometryJacobianFromHybridTerm()
Default Constructor.
Definition: RGBDOdometryJacobian.h:111
void ComputeJacobianAndResidual(int row, std::vector< Eigen::Vector6d, utility::Vector6d_allocator > &J_r, std::vector< double > &r, std::vector< double > &w, const geometry::RGBDImage &source, const geometry::RGBDImage &target, const geometry::Image &source_xyz, const geometry::RGBDImage &target_dx, const geometry::RGBDImage &target_dy, const Eigen::Matrix3d &intrinsic, const Eigen::Matrix4d &extrinsic, const CorrespondenceSetPixelWise &corresps) const override
Parameterized Constructor.
Definition: RGBDOdometryJacobian.cpp:71
Base class that computes Jacobian from two RGB-D images.
Definition: RGBDOdometryJacobian.h:37
virtual ~RGBDOdometryJacobian()
Definition: RGBDOdometryJacobian.h:41
virtual void ComputeJacobianAndResidual(int row, std::vector< Eigen::Vector6d, utility::Vector6d_allocator > &J_r, std::vector< double > &r, std::vector< double > &w, const geometry::RGBDImage &source, const geometry::RGBDImage &target, const geometry::Image &source_xyz, const geometry::RGBDImage &target_dx, const geometry::RGBDImage &target_dy, const Eigen::Matrix3d &intrinsic, const Eigen::Matrix4d &extrinsic, const CorrespondenceSetPixelWise &corresps) const =0
RGBDOdometryJacobian()
Default Constructor.
Definition: RGBDOdometryJacobian.h:40
std::vector< Eigen::Vector4i, utility::Vector4i_allocator > CorrespondenceSetPixelWise
Definition: RGBDOdometryJacobian.h:32
Definition: PinholeCameraIntrinsic.cpp:16