disabled two python tests

release/4.3a0
kartik arcot 2023-01-17 12:00:39 -08:00
parent 607a30a08e
commit d886e78afa
2 changed files with 7 additions and 7 deletions

View File

@ -20,6 +20,7 @@
#pragma once #pragma once
#include "gtsam/geometry/Point3.h"
#include <gtsam/geometry/Cal3Bundler.h> #include <gtsam/geometry/Cal3Bundler.h>
#include <gtsam/geometry/Cal3Fisheye.h> #include <gtsam/geometry/Cal3Fisheye.h>
#include <gtsam/geometry/Cal3Unified.h> #include <gtsam/geometry/Cal3Unified.h>
@ -33,6 +34,8 @@
#include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/slam/TriangulationFactor.h> #include <gtsam/slam/TriangulationFactor.h>
#include <optional>
namespace gtsam { namespace gtsam {
/// Exception thrown by triangulateDLT when SVD returns rank < 3 /// Exception thrown by triangulateDLT when SVD returns rank < 3
@ -656,6 +659,10 @@ class TriangulationResult : public std::optional<Point3> {
bool outlier() const { return status == OUTLIER; } bool outlier() const { return status == OUTLIER; }
bool farPoint() const { return status == FAR_POINT; } bool farPoint() const { return status == FAR_POINT; }
bool behindCamera() const { return status == BEHIND_CAMERA; } bool behindCamera() const { return status == BEHIND_CAMERA; }
const gtsam::Point3& get() const {
if (!has_value()) throw std::runtime_error("TriangulationResult has no value");
return value();
}
// stream to output // stream to output
friend std::ostream& operator<<(std::ostream& os, friend std::ostream& operator<<(std::ostream& os,
const TriangulationResult& result) { const TriangulationResult& result) {

View File

@ -12,13 +12,6 @@
*/ */
#include <pybind11/stl.h> #include <pybind11/stl.h>
// Support for binding boost::optional types in C++11.
// https://pybind11.readthedocs.io/en/stable/advanced/cast/stl.html
namespace pybind11 { namespace detail {
template <typename T>
struct type_caster<boost::optional<T>> : optional_caster<boost::optional<T>> {};
}}
PYBIND11_MAKE_OPAQUE( PYBIND11_MAKE_OPAQUE(
std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point2>>); std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point2>>);
PYBIND11_MAKE_OPAQUE(gtsam::Point2Pairs); PYBIND11_MAKE_OPAQUE(gtsam::Point2Pairs);