#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... | |
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.
|
inline |
|
inline |
bool gtsam::Event::equals | ( | const Event & | other, |
double | tol = 1e-9 |
||
) | const |
|
inline |
|
inline |
void gtsam::Event::print | ( | const std::string & | s = "" | ) | const |
|
inline |
|
private |