Public Types | Public Member Functions | Private Attributes | List of all members
gtsam::Event Class Reference

#include <Event.h>

Public Types

enum  { dimension = 4 }
 

Public Member Functions

GTSAM_UNSTABLE_EXPORT bool equals (const Event &other, double tol=1e-9) const
 
 Event ()
 Default Constructor. More...
 
 Event (double t, const Point3 &p)
 Constructor from time and location. More...
 
 Event (double t, double x, double y, double z)
 Constructor with doubles. More...
 
double height (OptionalJacobian< 1, 4 > H={}) const
 
Vector4 localCoordinates (const Event &q) const
 Returns inverse retraction. More...
 
Point3 location () const
 
GTSAM_UNSTABLE_EXPORT void print (const std::string &s="") const
 
Event retract (const Vector4 &v) const
 Updates a with tangent space delta. More...
 
double time () const
 

Private Attributes

Point3 location_
 Location at time event was generated. More...
 
double time_
 Time event was generated. More...
 

Detailed Description

A space-time event models an event that happens at a certain 3D location, at a certain time. One use for it is in sound-based or UWB-ranging tracking or SLAM, where we have "time of arrival" measurements at a set of sensors. The TOA functor below provides a measurement function for those applications.

Definition at line 37 of file Event.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
dimension 

Definition at line 42 of file Event.h.

Constructor & Destructor Documentation

◆ Event() [1/3]

gtsam::Event::Event ( )
inline

Default Constructor.

Definition at line 45 of file Event.h.

◆ Event() [2/3]

gtsam::Event::Event ( double  t,
const Point3 p 
)
inline

Constructor from time and location.

Definition at line 48 of file Event.h.

◆ Event() [3/3]

gtsam::Event::Event ( double  t,
double  x,
double  y,
double  z 
)
inline

Constructor with doubles.

Definition at line 51 of file Event.h.

Member Function Documentation

◆ equals()

bool gtsam::Event::equals ( const Event other,
double  tol = 1e-9 
) const

equals with an tolerance

Definition at line 32 of file Event.cpp.

◆ height()

double gtsam::Event::height ( OptionalJacobian< 1, 4 >  H = {}) const
inline

Definition at line 58 of file Event.h.

◆ localCoordinates()

Vector4 gtsam::Event::localCoordinates ( const Event q) const
inline

Returns inverse retraction.

Definition at line 77 of file Event.h.

◆ location()

Point3 gtsam::Event::location ( ) const
inline

Definition at line 55 of file Event.h.

◆ print()

void gtsam::Event::print ( const std::string &  s = "") const

print with optional string

Definition at line 26 of file Event.cpp.

◆ retract()

Event gtsam::Event::retract ( const Vector4 &  v) const
inline

Updates a with tangent space delta.

Definition at line 72 of file Event.h.

◆ time()

double gtsam::Event::time ( ) const
inline

Definition at line 54 of file Event.h.

Member Data Documentation

◆ location_

Point3 gtsam::Event::location_
private

Location at time event was generated.

Definition at line 39 of file Event.h.

◆ time_

double gtsam::Event::time_
private

Time event was generated.

Definition at line 38 of file Event.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:17