How to create bearing factors (without range)?

283 views
Skip to first unread message

S Chatzizacharias

unread,
Mar 12, 2021, 5:04:13 AM3/12/21
to gtsam users
Hello. I'm new to gtsam and I am trying to add some bearing factors in a nonlinear factor graph. The examples I found show only the bearing/range factor implementation. How can I do it without the range measurements? 

I tried this way:

// Create bearing factor from current pose to door point
Rot2 bearing_ang = Rot2::fromDegrees(13);
auto bearingNoise = noiseModel::Diagonal::Sigmas(Vector(0.1));
graph.emplace_shared<BearingFactor<Pose2, Point2>> (next_pose_num, next_door_num, bearing_ang, bearingNoise);

But I get a warning and an error while compiling:

/usr/local/include/gtsam/slam/BearingFactor.h:17:2: warning: #warning "BearingFactor is now an ExpressionFactor in SAM directory" [-Wcpp]
 #warning "BearingFactor is now an ExpressionFactor in SAM directory"

/usr/local/include/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h:778:7: error: static assertion failed: FLOATING_POINT_ARGUMENT_PASSED__INTEGER_WAS_EXPECTED
       EIGEN_STATIC_ASSERT(is_integer,

Also, I am not sure how to declare the bearing noise, since it is 1-dimensional measurement, so no matrix is required. 

Any feedback is appreciated.


Dellaert, Frank

unread,
Mar 12, 2021, 3:27:55 PM3/12/21
to S Chatzizacharias, gtsam users
There is a bearing-only factor if I am not mistaken

Frank

From: gtsam...@googlegroups.com <gtsam...@googlegroups.com> on behalf of S Chatzizacharias <spyros...@gmail.com>
Sent: Friday, March 12, 2021 5:04:13 AM
To: gtsam users <gtsam...@googlegroups.com>
Subject: [GTSAM] How to create bearing factors (without range)?
 
--
You received this message because you are subscribed to the Google Groups "gtsam users" group.
To unsubscribe from this group and stop receiving emails from it, send an email to gtsam-users...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/gtsam-users/60612849-3490-4e62-8664-8fed588d0099n%40googlegroups.com.

Dellaert, Frank

unread,
Mar 12, 2021, 3:29:35 PM3/12/21
to S Chatzizacharias, gtsam users
In sam directory, *not* slam :-)

Frank

From: gtsam...@googlegroups.com <gtsam...@googlegroups.com> on behalf of Dellaert, Frank <frank.d...@cc.gatech.edu>
Sent: Friday, March 12, 2021 3:27:53 PM
To: S Chatzizacharias <spyros...@gmail.com>; gtsam users <gtsam...@googlegroups.com>
Subject: Re: [GTSAM] How to create bearing factors (without range)?
 

S Chatzizacharias

unread,
Mar 15, 2021, 9:02:24 AM3/15/21
to gtsam users
Can you please direct me to some code samples that use this type of factor? (including the initialization and the noise model).

Also, I don't understand what that warning means. Should it be in the SLAM directory? and how can I change it? I don't remember choosing a directory to save it. I just include the header file:

#include <gtsam/slam/BearingFactor.h>

at the beginning of my code.

Dellaert, Frank

unread,
Mar 15, 2021, 9:32:03 AM3/15/21
to S Chatzizacharias, gtsam users
Please use

#include <gtsam/sam/BearingFactor.h>


Sent: Monday, March 15, 2021 09:02
To: gtsam users <gtsam...@googlegroups.com>

S Chatzizacharias

unread,
Mar 15, 2021, 9:48:16 AM3/15/21
to gtsam users
ok. Now I see. This removed the warning during compiling. Thanks!
Reply all
Reply to author
Forward
0 new messages