K() -> calibration()
parent
38922a38ac
commit
dbe7093f4d
|
|
@ -42,7 +42,7 @@ StereoPoint2 StereoCamera::project(const Point3& point,
|
||||||
Matrix D_intrinsic_cameraPoint = Dproject_to_stereo_camera1(cameraPoint); // 3x3 Jacobian
|
Matrix D_intrinsic_cameraPoint = Dproject_to_stereo_camera1(cameraPoint); // 3x3 Jacobian
|
||||||
Matrix D_intrinsic_pose = D_intrinsic_cameraPoint * D_cameraPoint_pose;
|
Matrix D_intrinsic_pose = D_intrinsic_cameraPoint * D_cameraPoint_pose;
|
||||||
|
|
||||||
Matrix D_projection_intrinsic = Duncalibrate2(K()); // 3x3
|
Matrix D_projection_intrinsic = Duncalibrate2(calibration()); // 3x3
|
||||||
*Dproject_stereo_pose = D_projection_intrinsic * D_intrinsic_pose;
|
*Dproject_stereo_pose = D_projection_intrinsic * D_intrinsic_pose;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@ -54,7 +54,7 @@ StereoPoint2 StereoCamera::project(const Point3& point,
|
||||||
Matrix D_intrinsic_cameraPoint = Dproject_to_stereo_camera1(cameraPoint); // 3x3 Jacobian
|
Matrix D_intrinsic_cameraPoint = Dproject_to_stereo_camera1(cameraPoint); // 3x3 Jacobian
|
||||||
Matrix D_intrinsic_point = D_intrinsic_cameraPoint * D_cameraPoint_point;
|
Matrix D_intrinsic_point = D_intrinsic_cameraPoint * D_cameraPoint_point;
|
||||||
|
|
||||||
Matrix D_projection_intrinsic = Duncalibrate2(K()); // 3x3
|
Matrix D_projection_intrinsic = Duncalibrate2(calibration()); // 3x3
|
||||||
*Dproject_stereo_point = D_projection_intrinsic * D_intrinsic_point;
|
*Dproject_stereo_point = D_projection_intrinsic * D_intrinsic_point;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -40,7 +40,7 @@ namespace gtsam {
|
||||||
|
|
||||||
StereoCamera(const Pose3& leftCamPose, const Cal3_S2Stereo& K);
|
StereoCamera(const Pose3& leftCamPose, const Cal3_S2Stereo& K);
|
||||||
|
|
||||||
const Cal3_S2Stereo& K() const {
|
const Cal3_S2Stereo& calibration() const {
|
||||||
return K_;
|
return K_;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@ -63,7 +63,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/** Exponential map around p0 */
|
/** Exponential map around p0 */
|
||||||
inline StereoCamera expmap(const Vector& d) const {
|
inline StereoCamera expmap(const Vector& d) const {
|
||||||
return StereoCamera(pose().expmap(d),K());
|
return StereoCamera(pose().expmap(d),calibration());
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector logmap(const StereoCamera &camera) const {
|
Vector logmap(const StereoCamera &camera) const {
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue