fixed paths to move Event from unstable
parent
f07d9aacd3
commit
c5a26aec59
|
@ -1514,7 +1514,17 @@ gtsam::TriangulationResult triangulateSafe(
|
|||
const gtsam::Point2Vector& measurements,
|
||||
const gtsam::TriangulationParameters& params);
|
||||
|
||||
|
||||
#include <gtsam_unstable/geometry/Event.h>
|
||||
class Event {
|
||||
Event();
|
||||
Event(double t, const gtsam::Point3& p);
|
||||
Event(double t, double x, double y, double z);
|
||||
double time() const;
|
||||
gtsam::Point3 location() const;
|
||||
TimeOfArrival();
|
||||
TimeOfArrival(double speed);
|
||||
double measure(const gtsam::Event& event, const gtsam::Point3& sensor) const;
|
||||
};
|
||||
|
||||
#include <gtsam/geometry/BearingRange.h>
|
||||
template <POSE, POINT, BEARING, RANGE>
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
#include <gtsam/nonlinear/expressions.h>
|
||||
#include <gtsam_unstable/geometry/Event.h>
|
||||
#include <gtsam/geometry/Event.h>
|
||||
#include <gtsam_unstable/slam/TOAFactor.h>
|
||||
|
||||
#include <vector>
|
||||
|
|
|
@ -379,22 +379,11 @@ virtual class RangeFactor : gtsam::NoiseModelFactor {
|
|||
|
||||
typedef gtsam::RangeFactor<gtsam::PoseRTV, gtsam::PoseRTV> RangeFactorRTV;
|
||||
|
||||
#include <gtsam_unstable/geometry/Event.h>
|
||||
class Event {
|
||||
Event();
|
||||
Event(double t, const gtsam::Point3& p);
|
||||
Event(double t, double x, double y, double z);
|
||||
double time() const;
|
||||
gtsam::Point3 location() const;
|
||||
double height() const;
|
||||
void print(string s) const;
|
||||
};
|
||||
|
||||
class TimeOfArrival {
|
||||
TimeOfArrival();
|
||||
TimeOfArrival(double speed);
|
||||
double measure(const gtsam::Event& event, const gtsam::Point3& sensor) const;
|
||||
};
|
||||
|
||||
#include <gtsam_unstable/slam/TOAFactor.h>
|
||||
virtual class TOAFactor : gtsam::NonlinearFactor {
|
||||
|
|
|
@ -11,11 +11,11 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef _MSC_VER
|
||||
#pragma message("IncrementalFixedLagSmoother was moved to the gtsam/nonlinear directory")
|
||||
#else
|
||||
#warning "IncrementalFixedLagSmoother was moved to the gtsam/nonlinear directory"
|
||||
#endif
|
||||
// #ifdef _MSC_VER
|
||||
// #pragma message("IncrementalFixedLagSmoother was moved to the gtsam/nonlinear directory")
|
||||
// #else
|
||||
// #warning "IncrementalFixedLagSmoother was moved to the gtsam/nonlinear directory"
|
||||
// #endif
|
||||
|
||||
|
||||
#include <gtsam/nonlinear/IncrementalFixedLagSmoother.h>
|
|
@ -20,7 +20,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <gtsam/nonlinear/ExpressionFactor.h>
|
||||
#include <gtsam_unstable/geometry/Event.h>
|
||||
#include <gtsam/geometry/Event.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
#include <gtsam/nonlinear/expressions.h>
|
||||
#include <gtsam_unstable/geometry/Event.h>
|
||||
#include <gtsam/geometry/Event.h>
|
||||
#include <gtsam_unstable/slam/TOAFactor.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
|
|
@ -12,8 +12,8 @@ Author: Frank Dellaert
|
|||
# pylint: disable=invalid-name, no-name-in-module
|
||||
|
||||
from gtsam import (LevenbergMarquardtOptimizer, LevenbergMarquardtParams,
|
||||
NonlinearFactorGraph, Point3, Values, noiseModel)
|
||||
from gtsam_unstable import Event, TimeOfArrival, TOAFactor
|
||||
NonlinearFactorGraph, Point3, Values, noiseModel, Event)
|
||||
from gtsam_unstable import TimeOfArrival, TOAFactor
|
||||
|
||||
# units
|
||||
MS = 1e-3
|
||||
|
|
Loading…
Reference in New Issue