Skip to content

Commit

Permalink
add interface for vSLAM
Browse files Browse the repository at this point in the history
  • Loading branch information
ydjian committed Sep 19, 2010
1 parent 14cb0be commit 3a11ec9
Show file tree
Hide file tree
Showing 2 changed files with 25 additions and 1 deletion.
17 changes: 17 additions & 0 deletions geometry/CalibratedCamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,5 +65,22 @@ namespace gtsam {
}
return project_to_camera(q);
}


CalibratedCamera CalibratedCamera::expmap(const Vector& d) const {
return CalibratedCamera(pose().expmap(d)) ;
}
Vector CalibratedCamera::logmap(const CalibratedCamera& T2) const {
return pose().logmap(T2.pose()) ;
}

CalibratedCamera CalibratedCamera::Expmap(const Vector& v) {
return CalibratedCamera(Pose3::Expmap(v)) ;
}

Vector CalibratedCamera::Logmap(const CalibratedCamera& p) {
return Pose3::Logmap(p.pose()) ;
}

/* ************************************************************************* */
}
9 changes: 8 additions & 1 deletion geometry/CalibratedCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,14 @@ namespace gtsam {
return CalibratedCamera( pose_.inverse() ) ;
}

inline static size_t dim() { return 6 ; }
CalibratedCamera expmap(const Vector& d) const;
Vector logmap(const CalibratedCamera& T2) const;

static CalibratedCamera Expmap(const Vector& v);
static Vector Logmap(const CalibratedCamera& p);

inline size_t dim() const { return 6 ; }
inline static size_t Dim() { return 6 ; }

/**
* Create a level camera at the given 2D pose and height
Expand Down

0 comments on commit 3a11ec9

Please sign in to comment.