#include <GPSPose2XYFactor.h>
|
gtsam::Vector | evaluateError (const gtsam::Pose2 &p, boost::optional< gtsam::Matrix & > H=boost::none) const |
|
| GPSPose2XYFactor (gtsam::Key poseKey, const gtsam::Point2 m, gtsam::SharedNoiseModel model) |
|
Definition at line 23 of file GPSPose2XYFactor.h.
rtabmap::GPSPose2XYFactor::GPSPose2XYFactor |
( |
gtsam::Key |
poseKey, |
|
|
const gtsam::Point2 |
m, |
|
|
gtsam::SharedNoiseModel |
model |
|
) |
| |
|
inline |
Constructor
- Parameters
-
poseKey | associated pose varible key |
model | noise model for GPS snesor, in X-Y |
m | Point2 measurement |
Definition at line 37 of file GPSPose2XYFactor.h.
gtsam::Vector rtabmap::GPSPose2XYFactor::evaluateError |
( |
const gtsam::Pose2 & |
p, |
|
|
boost::optional< gtsam::Matrix & > |
H = boost::none |
|
) |
| const |
|
inline |
double rtabmap::GPSPose2XYFactor::mx_ |
|
private |
double rtabmap::GPSPose2XYFactor::my_ |
|
private |
The documentation for this class was generated from the following file: