#include <pose_rotation_factor.h>
|
| PoseRotationFactor () |
|
| PoseRotationFactor (const Rot3 &rotation, const SharedNoiseModel &model, Key pose_key_1, Key pose_key_2) |
|
gtsam::NonlinearFactor::shared_ptr | clone () const override |
|
void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
|
bool | equals (const NonlinearFactor &p, double tol=1e-9) const override |
|
Vector | evaluateError (const Pose3 &pose1, const Pose3 &pose2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override |
|
const Rot3 & | rotation () const |
|
◆ PoseRotationFactor() [1/2]
gtsam::PoseRotationFactor::PoseRotationFactor |
( |
| ) |
|
|
inline |
◆ PoseRotationFactor() [2/2]
gtsam::PoseRotationFactor::PoseRotationFactor |
( |
const Rot3 & |
rotation, |
|
|
const SharedNoiseModel & |
model, |
|
|
Key |
pose_key_1, |
|
|
Key |
pose_key_2 |
|
) |
| |
|
inline |
◆ clone()
gtsam::NonlinearFactor::shared_ptr gtsam::PoseRotationFactor::clone |
( |
| ) |
const |
|
inlineoverride |
◆ equals()
bool gtsam::PoseRotationFactor::equals |
( |
const NonlinearFactor & |
p, |
|
|
double |
tol = 1e-9 |
|
) |
| const |
|
inlineoverride |
◆ evaluateError()
Vector gtsam::PoseRotationFactor::evaluateError |
( |
const Pose3 & |
pose1, |
|
|
const Pose3 & |
pose2, |
|
|
boost::optional< Matrix & > |
H1 = boost::none , |
|
|
boost::optional< Matrix & > |
H2 = boost::none |
|
) |
| const |
|
inlineoverride |
◆ print()
void gtsam::PoseRotationFactor::print |
( |
const std::string & |
s = "" , |
|
|
const KeyFormatter & |
keyFormatter = DefaultKeyFormatter |
|
) |
| const |
|
inlineoverride |
◆ rotation()
const Rot3& gtsam::PoseRotationFactor::rotation |
( |
| ) |
const |
|
inline |
◆ boost::serialization::access
friend class boost::serialization::access |
|
friend |
The documentation for this class was generated from the following file: