Skip to content

Commit

Permalink
Merge pull request #105 from borglab/fix/smartFactors
Browse files Browse the repository at this point in the history
Fix/smart factors
  • Loading branch information
mikesheffler authored Aug 27, 2019
2 parents 66ca635 + 20736b6 commit 033a307
Show file tree
Hide file tree
Showing 7 changed files with 180 additions and 214 deletions.
3 changes: 3 additions & 0 deletions gtsam.h
Original file line number Diff line number Diff line change
Expand Up @@ -2499,6 +2499,9 @@ virtual class SmartProjectionPoseFactor: gtsam::NonlinearFactor {
SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise,
const CALIBRATION* K,
const gtsam::Pose3& body_P_sensor);
SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise,
const CALIBRATION* K,
const gtsam::SmartProjectionParams& params);
SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise,
const CALIBRATION* K,
const gtsam::Pose3& body_P_sensor,
Expand Down
2 changes: 1 addition & 1 deletion gtsam/navigation/AHRSFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,8 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation
const Rot3& deltaRij,
const Matrix3& delRdelBiasOmega,
const Matrix3& preint_meas_cov) :
biasHat_(bias_hat),
PreintegratedRotation(p, deltaTij, deltaRij, delRdelBiasOmega),
biasHat_(bias_hat),
preintMeasCov_(preint_meas_cov) {}

const Params& p() const { return *boost::static_pointer_cast<const Params>(p_);}
Expand Down
26 changes: 13 additions & 13 deletions gtsam/slam/SmartFactorBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,15 +75,12 @@ class SmartFactorBase: public NonlinearFactor {
*/
ZVector measured_;

/// @name Pose of the camera in the body frame
boost::optional<Pose3> body_P_sensor_; ///< Pose of the camera in the body frame
/// @}
boost::optional<Pose3> body_P_sensor_; ///< Pose of the camera in the body frame

// Cache for Fblocks, to avoid a malloc ever time we re-linearize
mutable FBlocks Fs;

public:

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

/// shorthand for a smart pointer to a factor
Expand Down Expand Up @@ -200,17 +197,20 @@ class SmartFactorBase: public NonlinearFactor {
return e && Base::equals(p, tol) && areMeasurementsEqual;
}

/// Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives
template<class POINT>
Vector unwhitenedError(const Cameras& cameras, const POINT& point,
boost::optional<typename Cameras::FBlocks&> Fs = boost::none, //
/// Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and
/// derivatives
template <class POINT>
Vector unwhitenedError(
const Cameras& cameras, const POINT& point,
boost::optional<typename Cameras::FBlocks&> Fs = boost::none, //
boost::optional<Matrix&> E = boost::none) const {
Vector ue = cameras.reprojectionError(point, measured_, Fs, E);
if(body_P_sensor_ && Fs){
for(size_t i=0; i < Fs->size(); i++){
Pose3 w_Pose_body = (cameras[i].pose()).compose(body_P_sensor_->inverse());
if (body_P_sensor_ && Fs) {
const Pose3 sensor_P_body = body_P_sensor_->inverse();
for (size_t i = 0; i < Fs->size(); i++) {
const Pose3 w_Pose_body = cameras[i].pose() * sensor_P_body;
Matrix J(6, 6);
Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J);
const Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J);
Fs->at(i) = Fs->at(i) * J;
}
}
Expand Down
37 changes: 28 additions & 9 deletions gtsam/slam/SmartProjectionFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,15 +79,15 @@ class SmartProjectionFactor: public SmartFactorBase<CAMERA> {

/**
* Constructor
* @param body_P_sensor pose of the camera in the body frame
* @param params internal parameters of the smart factors
* @param sharedNoiseModel isotropic noise model for the 2D feature measurements
* @param params parameters for the smart projection factors
*/
SmartProjectionFactor(const SharedNoiseModel& sharedNoiseModel,
const boost::optional<Pose3> body_P_sensor = boost::none,
const SmartProjectionParams& params = SmartProjectionParams()) :
Base(sharedNoiseModel, body_P_sensor), params_(params), //
result_(TriangulationResult::Degenerate()) {
}
SmartProjectionFactor(
const SharedNoiseModel& sharedNoiseModel,
const SmartProjectionParams& params = SmartProjectionParams())
: Base(sharedNoiseModel),
params_(params),
result_(TriangulationResult::Degenerate()) {}

/** Virtual destructor */
virtual ~SmartProjectionFactor() {
Expand Down Expand Up @@ -443,7 +443,26 @@ class SmartProjectionFactor: public SmartFactorBase<CAMERA> {
/** return the farPoint state */
bool isFarPoint() const { return result_.farPoint(); }

private:
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
/// @name Deprecated
/// @{
// It does not make sense to optimize for a camera where the pose would not be
// the actual pose of the camera. An unfortunate consequence of deprecating
// this constructor means that we cannot optimize for calibration when the
// camera is offset from the body pose. That would need a new factor with
// (body) pose and calibration as variables. However, that use case is
// unlikely: when a global offset is know, calibration is typically known.
SmartProjectionFactor(
const SharedNoiseModel& sharedNoiseModel,
const boost::optional<Pose3> body_P_sensor,
const SmartProjectionParams& params = SmartProjectionParams())
: Base(sharedNoiseModel, body_P_sensor),
params_(params),
result_(TriangulationResult::Degenerate()) {}
/// @}
#endif

private:

/// Serialization function
friend class boost::serialization::access;
Expand Down
43 changes: 28 additions & 15 deletions gtsam/slam/SmartProjectionPoseFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,16 +66,31 @@ class SmartProjectionPoseFactor: public SmartProjectionFactor<

/**
* Constructor
* @param Isotropic measurement noise
* @param sharedNoiseModel isotropic noise model for the 2D feature measurements
* @param K (fixed) calibration, assumed to be the same for all cameras
* @param body_P_sensor pose of the camera in the body frame
* @param params internal parameters of the smart factors
* @param params parameters for the smart projection factors
*/
SmartProjectionPoseFactor(const SharedNoiseModel& sharedNoiseModel,
SmartProjectionPoseFactor(
const SharedNoiseModel& sharedNoiseModel,
const boost::shared_ptr<CALIBRATION> K,
const boost::optional<Pose3> body_P_sensor = boost::none,
const SmartProjectionParams& params = SmartProjectionParams()) :
Base(sharedNoiseModel, body_P_sensor, params), K_(K) {
const SmartProjectionParams& params = SmartProjectionParams())
: Base(sharedNoiseModel, params), K_(K) {
}

/**
* Constructor
* @param sharedNoiseModel isotropic noise model for the 2D feature measurements
* @param K (fixed) calibration, assumed to be the same for all cameras
* @param body_P_sensor pose of the camera in the body frame (optional)
* @param params parameters for the smart projection factors
*/
SmartProjectionPoseFactor(
const SharedNoiseModel& sharedNoiseModel,
const boost::shared_ptr<CALIBRATION> K,
const boost::optional<Pose3> body_P_sensor,
const SmartProjectionParams& params = SmartProjectionParams())
: SmartProjectionPoseFactor(sharedNoiseModel, K, params) {
this->body_P_sensor_ = body_P_sensor;
}

/** Virtual destructor */
Expand Down Expand Up @@ -123,18 +138,16 @@ class SmartProjectionPoseFactor: public SmartProjectionFactor<
*/
typename Base::Cameras cameras(const Values& values) const {
typename Base::Cameras cameras;
for(const Key& k: this->keys_) {
Pose3 pose = values.at<Pose3>(k);
if (Base::body_P_sensor_)
pose = pose.compose(*(Base::body_P_sensor_));

Camera camera(pose, K_);
cameras.push_back(camera);
for (const Key& k : this->keys_) {
const Pose3 world_P_sensor_k =
Base::body_P_sensor_ ? values.at<Pose3>(k) * *Base::body_P_sensor_
: values.at<Pose3>(k);
cameras.emplace_back(world_P_sensor_k, K_);
}
return cameras;
}

private:
private:

/// Serialization function
friend class boost::serialization::access;
Expand Down
Loading

0 comments on commit 033a307

Please sign in to comment.