TAvg wrapper builds
							parent
							
								
									9b481cb790
								
							
						
					
					
						commit
						7ffa54f896
					
				| 
						 | 
				
			
			@ -2914,6 +2914,13 @@ class BinaryMeasurement {
 | 
			
		|||
typedef gtsam::BinaryMeasurement<gtsam::Unit3> BinaryMeasurementUnit3;
 | 
			
		||||
typedef gtsam::BinaryMeasurement<gtsam::Rot3> BinaryMeasurementRot3;
 | 
			
		||||
 | 
			
		||||
class BinaryMeasurementsUnit3 {
 | 
			
		||||
  BinaryMeasurementsUnit3();
 | 
			
		||||
  size_t size() const;
 | 
			
		||||
  gtsam::BinaryMeasurement<gtsam::Unit3> at(size_t idx) const;
 | 
			
		||||
  void push_back(const gtsam::BinaryMeasurement<gtsam::Unit3> measurement);
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
#include <gtsam/sfm/ShonanAveraging.h>
 | 
			
		||||
 | 
			
		||||
// TODO(frank): copy/pasta below until we have integer template paremeters in wrap!
 | 
			
		||||
| 
						 | 
				
			
			@ -3035,11 +3042,10 @@ class ShonanAveraging3 {
 | 
			
		|||
 | 
			
		||||
#include <gtsam/sfm/TranslationRecovery.h>
 | 
			
		||||
class TranslationRecovery {
 | 
			
		||||
  TranslationRecovery(const BinaryMeasurementsUnit3& relativeTranslations,
 | 
			
		||||
                      const LevenbergMarquardtParams& lmParams);
 | 
			
		||||
  TranslationRecovery(const gtsam::BinaryMeasurementsUnit3 &relativeTranslations,
 | 
			
		||||
                      const gtsam::LevenbergMarquardtParams &lmParams);
 | 
			
		||||
  TranslationRecovery(
 | 
			
		||||
      const BinaryMeasurementsUnit3&
 | 
			
		||||
          relativeTranslations);  // default LevenbergMarquardtParams
 | 
			
		||||
      const gtsam::BinaryMeasurementsUnit3 & relativeTranslations);  // default LevenbergMarquardtParams
 | 
			
		||||
  gtsam::Values run(const double scale) const;
 | 
			
		||||
  gtsam::Values run() const;    // default scale = 1.0
 | 
			
		||||
};
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -354,6 +354,7 @@ parse3DFactors(const std::string &filename,
 | 
			
		|||
               const noiseModel::Diagonal::shared_ptr &model = nullptr,
 | 
			
		||||
               size_t maxIndex = 0);
 | 
			
		||||
 | 
			
		||||
using BinaryMeasurementsUnit3 = std::vector<BinaryMeasurement<Unit3>>;
 | 
			
		||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
 | 
			
		||||
inline boost::optional<IndexedPose> parseVertex(std::istream &is,
 | 
			
		||||
                                                const std::string &tag) {
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -30,7 +30,8 @@ set(ignore
 | 
			
		|||
    gtsam::BetweenFactorPose3s
 | 
			
		||||
    gtsam::Point2Vector
 | 
			
		||||
    gtsam::Pose3Vector
 | 
			
		||||
    gtsam::KeyVector)
 | 
			
		||||
    gtsam::KeyVector
 | 
			
		||||
    gtsam::BinaryMeasurementsUnit3)
 | 
			
		||||
 | 
			
		||||
pybind_wrap(gtsam_py # target
 | 
			
		||||
            ${PROJECT_SOURCE_DIR}/gtsam/gtsam.i # interface_header
 | 
			
		||||
| 
						 | 
				
			
			@ -72,7 +73,8 @@ set(ignore
 | 
			
		|||
        gtsam::Point2Vector
 | 
			
		||||
        gtsam::Pose3Vector
 | 
			
		||||
        gtsam::KeyVector
 | 
			
		||||
        gtsam::FixedLagSmootherKeyTimestampMapValue)
 | 
			
		||||
        gtsam::FixedLagSmootherKeyTimestampMapValue
 | 
			
		||||
        gtsam::BinaryMeasurementsUnit3)
 | 
			
		||||
pybind_wrap(gtsam_unstable_py # target
 | 
			
		||||
        ${PROJECT_SOURCE_DIR}/gtsam_unstable/gtsam_unstable.i # interface_header
 | 
			
		||||
        "gtsam_unstable.cpp" # generated_cpp
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
		Loading…
	
		Reference in New Issue