fixed paths to move Event from unstable
parent
f07d9aacd3
commit
c5a26aec59
|
@ -213,7 +213,7 @@ namespace so3 {
|
||||||
ExpmapFunctor(const gtsam::Vector3& axis, double angle);
|
ExpmapFunctor(const gtsam::Vector3& axis, double angle);
|
||||||
gtsam::Matrix3 expmap() const;
|
gtsam::Matrix3 expmap() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
virtual class DexpFunctor : gtsam::so3::ExpmapFunctor {
|
virtual class DexpFunctor : gtsam::so3::ExpmapFunctor {
|
||||||
const gtsam::Vector3 omega;
|
const gtsam::Vector3 omega;
|
||||||
const double C; // (1 - A) / theta^2
|
const double C; // (1 - A) / theta^2
|
||||||
|
@ -228,7 +228,7 @@ namespace so3 {
|
||||||
gtsam::Vector3 applyRightJacobianInverse(const gtsam::Vector3& v) const;
|
gtsam::Vector3 applyRightJacobianInverse(const gtsam::Vector3& v) const;
|
||||||
gtsam::Vector3 applyLeftJacobian(const gtsam::Vector3& v) const;
|
gtsam::Vector3 applyLeftJacobian(const gtsam::Vector3& v) const;
|
||||||
gtsam::Vector3 applyLeftJacobianInverse(const gtsam::Vector3& v) const;
|
gtsam::Vector3 applyLeftJacobianInverse(const gtsam::Vector3& v) const;
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
class SO3 {
|
class SO3 {
|
||||||
|
@ -427,7 +427,7 @@ class Rot3 {
|
||||||
Eigen::Ref<Eigen::MatrixXd> HR,
|
Eigen::Ref<Eigen::MatrixXd> HR,
|
||||||
Eigen::Ref<Eigen::MatrixXd> Hp) const;
|
Eigen::Ref<Eigen::MatrixXd> Hp) const;
|
||||||
gtsam::Unit3 unrotate(const gtsam::Unit3& p) const;
|
gtsam::Unit3 unrotate(const gtsam::Unit3& p) const;
|
||||||
|
|
||||||
// Standard Interface
|
// Standard Interface
|
||||||
gtsam::Matrix matrix() const;
|
gtsam::Matrix matrix() const;
|
||||||
gtsam::Matrix transpose() const;
|
gtsam::Matrix transpose() const;
|
||||||
|
@ -522,7 +522,7 @@ class Pose2 {
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/geometry/Pose3.h>
|
#include <gtsam/geometry/Pose3.h>
|
||||||
class Pose3 {
|
class Pose3 {
|
||||||
// Standard Constructors
|
// Standard Constructors
|
||||||
|
@ -573,12 +573,12 @@ class Pose3 {
|
||||||
static gtsam::Matrix6 LogmapDerivative(const gtsam::Pose3& xi);
|
static gtsam::Matrix6 LogmapDerivative(const gtsam::Pose3& xi);
|
||||||
static gtsam::Pose3 Expmap(gtsam::Vector xi, Eigen::Ref<Eigen::MatrixXd> Hxi);
|
static gtsam::Pose3 Expmap(gtsam::Vector xi, Eigen::Ref<Eigen::MatrixXd> Hxi);
|
||||||
static gtsam::Vector Logmap(const gtsam::Pose3& pose, Eigen::Ref<Eigen::MatrixXd> Hpose);
|
static gtsam::Vector Logmap(const gtsam::Pose3& pose, Eigen::Ref<Eigen::MatrixXd> Hpose);
|
||||||
|
|
||||||
gtsam::Pose3 expmap(gtsam::Vector v);
|
gtsam::Pose3 expmap(gtsam::Vector v);
|
||||||
gtsam::Pose3 expmap(gtsam::Vector v, Eigen::Ref<Eigen::MatrixXd> H1, Eigen::Ref<Eigen::MatrixXd> H2);
|
gtsam::Pose3 expmap(gtsam::Vector v, Eigen::Ref<Eigen::MatrixXd> H1, Eigen::Ref<Eigen::MatrixXd> H2);
|
||||||
gtsam::Vector logmap(const gtsam::Pose3& p);
|
gtsam::Vector logmap(const gtsam::Pose3& p);
|
||||||
gtsam::Vector logmap(const gtsam::Pose3& p, Eigen::Ref<Eigen::MatrixXd> H1, Eigen::Ref<Eigen::MatrixXd> H2);
|
gtsam::Vector logmap(const gtsam::Pose3& p, Eigen::Ref<Eigen::MatrixXd> H1, Eigen::Ref<Eigen::MatrixXd> H2);
|
||||||
|
|
||||||
gtsam::Matrix AdjointMap() const;
|
gtsam::Matrix AdjointMap() const;
|
||||||
gtsam::Vector Adjoint(gtsam::Vector xi_b) const;
|
gtsam::Vector Adjoint(gtsam::Vector xi_b) const;
|
||||||
gtsam::Vector Adjoint(gtsam::Vector xi_b, Eigen::Ref<Eigen::MatrixXd> H_this,
|
gtsam::Vector Adjoint(gtsam::Vector xi_b, Eigen::Ref<Eigen::MatrixXd> H_this,
|
||||||
|
@ -718,7 +718,7 @@ class OrientedPlane3 {
|
||||||
|
|
||||||
static size_t Dim();
|
static size_t Dim();
|
||||||
size_t dim() const;
|
size_t dim() const;
|
||||||
|
|
||||||
gtsam::OrientedPlane3 retract(const gtsam::Vector3& v) const;
|
gtsam::OrientedPlane3 retract(const gtsam::Vector3& v) const;
|
||||||
gtsam::OrientedPlane3 retract(const gtsam::Vector3& v,
|
gtsam::OrientedPlane3 retract(const gtsam::Vector3& v,
|
||||||
Eigen::Ref<Eigen::MatrixXd> H) const;
|
Eigen::Ref<Eigen::MatrixXd> H) const;
|
||||||
|
@ -1491,7 +1491,7 @@ gtsam::TriangulationResult triangulateSafe(
|
||||||
const gtsam::Point2Vector& measurements,
|
const gtsam::Point2Vector& measurements,
|
||||||
const gtsam::TriangulationParameters& params);
|
const gtsam::TriangulationParameters& params);
|
||||||
|
|
||||||
// Cal3Unified versions
|
// Cal3Unified versions
|
||||||
gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses,
|
gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses,
|
||||||
gtsam::Cal3Unified* sharedCal,
|
gtsam::Cal3Unified* sharedCal,
|
||||||
const gtsam::Point2Vector& measurements,
|
const gtsam::Point2Vector& measurements,
|
||||||
|
@ -1514,7 +1514,17 @@ gtsam::TriangulationResult triangulateSafe(
|
||||||
const gtsam::Point2Vector& measurements,
|
const gtsam::Point2Vector& measurements,
|
||||||
const gtsam::TriangulationParameters& params);
|
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>
|
#include <gtsam/geometry/BearingRange.h>
|
||||||
template <POSE, POINT, BEARING, RANGE>
|
template <POSE, POINT, BEARING, RANGE>
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||||
#include <gtsam/nonlinear/expressions.h>
|
#include <gtsam/nonlinear/expressions.h>
|
||||||
#include <gtsam_unstable/geometry/Event.h>
|
#include <gtsam/geometry/Event.h>
|
||||||
#include <gtsam_unstable/slam/TOAFactor.h>
|
#include <gtsam_unstable/slam/TOAFactor.h>
|
||||||
|
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
|
@ -162,7 +162,7 @@ class BearingS2 {
|
||||||
void serializable() const; // enabling serialization functionality
|
void serializable() const; // enabling serialization functionality
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
#include <gtsam_unstable/geometry/SimWall2D.h>
|
#include <gtsam_unstable/geometry/SimWall2D.h>
|
||||||
class SimWall2D {
|
class SimWall2D {
|
||||||
SimWall2D();
|
SimWall2D();
|
||||||
|
@ -379,22 +379,11 @@ virtual class RangeFactor : gtsam::NoiseModelFactor {
|
||||||
|
|
||||||
typedef gtsam::RangeFactor<gtsam::PoseRTV, gtsam::PoseRTV> RangeFactorRTV;
|
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;
|
double height() const;
|
||||||
void print(string s) const;
|
void print(string s) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
class TimeOfArrival {
|
class TimeOfArrival {
|
||||||
TimeOfArrival();
|
|
||||||
TimeOfArrival(double speed);
|
|
||||||
double measure(const gtsam::Event& event, const gtsam::Point3& sensor) const;
|
|
||||||
};
|
|
||||||
|
|
||||||
#include <gtsam_unstable/slam/TOAFactor.h>
|
#include <gtsam_unstable/slam/TOAFactor.h>
|
||||||
virtual class TOAFactor : gtsam::NonlinearFactor {
|
virtual class TOAFactor : gtsam::NonlinearFactor {
|
||||||
|
|
|
@ -11,11 +11,11 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#ifdef _MSC_VER
|
// #ifdef _MSC_VER
|
||||||
#pragma message("IncrementalFixedLagSmoother was moved to the gtsam/nonlinear directory")
|
// #pragma message("IncrementalFixedLagSmoother was moved to the gtsam/nonlinear directory")
|
||||||
#else
|
// #else
|
||||||
#warning "IncrementalFixedLagSmoother was moved to the gtsam/nonlinear directory"
|
// #warning "IncrementalFixedLagSmoother was moved to the gtsam/nonlinear directory"
|
||||||
#endif
|
// #endif
|
||||||
|
|
||||||
|
|
||||||
#include <gtsam/nonlinear/IncrementalFixedLagSmoother.h>
|
#include <gtsam/nonlinear/IncrementalFixedLagSmoother.h>
|
||||||
|
|
|
@ -20,7 +20,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <gtsam/nonlinear/ExpressionFactor.h>
|
#include <gtsam/nonlinear/ExpressionFactor.h>
|
||||||
#include <gtsam_unstable/geometry/Event.h>
|
#include <gtsam/geometry/Event.h>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||||
#include <gtsam/nonlinear/expressions.h>
|
#include <gtsam/nonlinear/expressions.h>
|
||||||
#include <gtsam_unstable/geometry/Event.h>
|
#include <gtsam/geometry/Event.h>
|
||||||
#include <gtsam_unstable/slam/TOAFactor.h>
|
#include <gtsam_unstable/slam/TOAFactor.h>
|
||||||
|
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
|
@ -12,8 +12,8 @@ Author: Frank Dellaert
|
||||||
# pylint: disable=invalid-name, no-name-in-module
|
# pylint: disable=invalid-name, no-name-in-module
|
||||||
|
|
||||||
from gtsam import (LevenbergMarquardtOptimizer, LevenbergMarquardtParams,
|
from gtsam import (LevenbergMarquardtOptimizer, LevenbergMarquardtParams,
|
||||||
NonlinearFactorGraph, Point3, Values, noiseModel)
|
NonlinearFactorGraph, Point3, Values, noiseModel, Event)
|
||||||
from gtsam_unstable import Event, TimeOfArrival, TOAFactor
|
from gtsam_unstable import TimeOfArrival, TOAFactor
|
||||||
|
|
||||||
# units
|
# units
|
||||||
MS = 1e-3
|
MS = 1e-3
|
||||||
|
|
Loading…
Reference in New Issue