Skip to content

Commit

Permalink
Merge pull request #814 from borglab/fix/misc
Browse files Browse the repository at this point in the history
  • Loading branch information
varunagrawal authored Jul 9, 2021
2 parents cd3854a + d7d9ac0 commit 4fc6859
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 1 deletion.
2 changes: 1 addition & 1 deletion gtsam/geometry/Pose3.h
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ class GTSAM_EXPORT Pose3: public LieGroup<Pose3, 6> {
static Vector6 Logmap(const Pose3& pose, OptionalJacobian<6, 6> Hpose = boost::none);

/**
* Calculate Adjoint map, transforming a twist in the this pose's (i.e, body) frame to the world spatial frame
* Calculate Adjoint map, transforming a twist in this pose's (i.e, body) frame to the world spatial frame
* Ad_pose is 6*6 matrix that when applied to twist xi \f$ [R_x,R_y,R_z,T_x,T_y,T_z] \f$, returns Ad_pose(xi)
*/
Matrix6 AdjointMap() const; /// FIXME Not tested - marked as incorrect
Expand Down
1 change: 1 addition & 0 deletions gtsam/gtsam.i
Original file line number Diff line number Diff line change
Expand Up @@ -690,6 +690,7 @@ class Pose3 {
// Lie Group
static gtsam::Pose3 Expmap(Vector v);
static Vector Logmap(const gtsam::Pose3& pose);
gtsam::Pose3 expmap(Vector v);
Vector logmap(const gtsam::Pose3& pose);
Matrix AdjointMap() const;
Vector Adjoint(Vector xi) const;
Expand Down

0 comments on commit 4fc6859

Please sign in to comment.