Variables in Caesar.jl
You can check for the latest variable types by running the following in your terminal:
using RoME, Caesar
subtypes(IncrementalInference.InferenceVariable)
IncrementalInference.getCurrentWorkspaceVariables()
Default variables in IncrementalInference
struct ContinuousScalar <: InferenceVariable
Most basic continuous scalar variable a ::FactorGraph
object.
struct ContinuousMultivariate{T1<:Tuple} <: InferenceVariable
Continuous variable of dimension .dims
on manifold .manifolds
.
2D Variables
The current variables types are:
RoME.Point2
— Type.struct Point2 <: InferenceVariable
XY Euclidean manifold variable node softtype.
RoME.Pose2
— Type.struct Pose2 <: InferenceVariable
Pose2 is a SE(2) mechanization of two Euclidean translations and one Circular rotation, used for general 2D SLAM.
RoME.DynPoint2
— Type.mutable struct DynPoint2 <: InferenceVariable
Dynamic point in 2D space with velocity components: x, y, dx/dt, dy/dt
RoME.DynPose2
— Type.mutable struct DynPose2 <: InferenceVariable
Dynamic pose variable with velocity components: x, y, theta, dx/dt, dy/dt
3D Variables
RoME.Point3
— Type.struct Point3 <: InferenceVariable
XYZ Euclidean manifold variable node softtype.
Example
p3 = Point3()
RoME.Pose3
— Type.struct Pose3 <: InferenceVariable
Pose3 is currently a Euler angle mechanization of three Euclidean translations and three Circular rotation.
Future:
- Work in progress on AMP3D for proper non-Euler angle on-manifold operations.
RoME.InertialPose3
— Type.mutable struct InertialPose3 <: FunctorPairwise
Inertial Odometry version of preintegration procedure and used as a factor between InertialPose3 types for inertial navigation in factor graphs.
Note Please open an issue with JuliaRobotics/RoME.jl for specific requests, problems, or suggestions. Contributions are also welcome.
Note There might be more variable types in Caesar/RoME/IIF not yet documented here.
Factors in Caesar.jl
You can check for the latest factor types by running the following in your terminal:
using RoME, Caesar
println("- Singletons (priors): ")
println.(sort(string.(subtypes(IncrementalInference.FunctorSingleton))));
println("- Pairwise (variable constraints): ")
println.(sort(string.(subtypes(IncrementalInference.FunctorPairwise))));
println("- Pairwise (variable minimization constraints): ")
println.(sort(string.(subtypes(IncrementalInference.FunctorPairwiseMinimize))));
Priors (Absolute Data)
Existing prior (unary) factors in Caesar.jl/RoME.jl/IIF.jl include:
RoME.PriorPoint2
— Type.mutable struct PriorPoint2{T} <: FunctorSingleton
Direction observation information of a Point2
variable.
RoME.PriorPose2
— Type.mutable struct PriorPose2{T} <: FunctorSingleton
Introduce direct observations on all dimensions of a Pose2 variable:
Example:
PriorPose2( MvNormal([10; 10; pi/6.0], Matrix(Diagonal([0.1;0.1;0.05].^2))) )
RoME.PriorPolar
— Type.mutable struct PriorPolar{T1<:Union{AliasingScalarSampler, BallTreeDensity, Distribution}, T2<:Union{AliasingScalarSampler, BallTreeDensity, Distribution}} <: FunctorSingleton
Prior 3D (unary) factors
RoME.PriorPoint3
— Type.mutable struct PriorPoint3{T} <: FunctorSingleton
Direction observation information of a Point3
variable.
RoME.PriorPose3
— Type.mutable struct PriorPose3 <: FunctorSingleton
Direct observation information of Pose3
variable type.
Defaults in IncrementalInference.jl:
IncrementalInference.Prior
— Type.struct Prior{T} <: FunctorSingleton
Default prior on all dimensions of a variable node in the factor graph. Prior
is not recommended when non-Euclidean dimensions are used in variables.
struct PartialPrior{T, P} <: FunctorSingleton
Partial prior belief (absolute data) on any variable, given <:SamplableBelief
and which dimensions of the intended variable.
struct MixturePrior{T} <: FunctorSingleton
Define a categorical mixture of prior beliefs on a variable.
Conditional Likelihoods (Relative Data)
Existing n-ary factors in Caesar.jl/RoME.jl/IIF.jl include:
RoME.Point2Point2
— Type.mutable struct Point2Point2{D<:Union{AliasingScalarSampler, BallTreeDensity, Distribution}} <: FunctorPairwise
RoME.Point2Point2WorldBearing
— Type.mutable struct Point2Point2WorldBearing{T} <: FunctorPairwise
RoME.Pose2Point2Bearing
— Type.mutable struct Pose2Point2Bearing{B<:Union{AliasingScalarSampler, BallTreeDensity, Distribution}} <: FunctorPairwiseMinimize
Single dimension bearing constraint from Pose2 to Point2 variable.
RoME.Pose2Point2BearingRange
— Type.mutable struct Pose2Point2BearingRange{B<:Union{AliasingScalarSampler, BallTreeDensity, Distribution}, R<:Union{AliasingScalarSampler, BallTreeDensity, Distribution}} <: FunctorPairwise
Bearing and Range constraint from a Pose2 to Point2 variable.
RoME.Pose2Point2Range
— Type.mutable struct Pose2Point2Range{T} <: FunctorPairwise
Range only measurement from Pose2 to Point2 variable.
RoME.Pose2Pose2
— Type.mutable struct Pose2Pose2{T} <: FunctorPairwise
RoME.DynPoint2VelocityPrior
— Type.mutable struct DynPoint2VelocityPrior{T} <: FunctorSingleton
RoME.DynPoint2DynPoint2
— Type.mutable struct DynPoint2DynPoint2{T} <: FunctorPairwise
RoME.VelPoint2VelPoint2
— Type.mutable struct VelPoint2VelPoint2{T} <: FunctorPairwiseMinimize
RoME.Point2Point2Velocity
— Type.mutable struct Point2Point2Velocity{T} <: FunctorPairwiseMinimize
RoME.DynPose2VelocityPrior
— Type.mutable struct DynPose2VelocityPrior{T1, T2} <: FunctorSingleton
RoME.VelPose2VelPose2
— Type.mutable struct VelPose2VelPose2{T1, T2} <: FunctorPairwiseMinimize
RoME.DynPose2Pose2
— Type.mutable struct DynPose2Pose2{T} <: FunctorPairwise
RoME.Pose3Pose3
— Type.mutable struct Pose3Pose3 <: FunctorPairwise
Rigid transform factor between two Pose3 compliant variables.
Missing docstring for InertialPose3
. Check Documenter's build log for details.
RoME.PriorPose3ZRP
— Type.mutable struct PriorPose3ZRP{T1, T2} <: FunctorSingleton
Partial prior belief on Z, Roll, and Pitch of a Pose3
.
RoME.PartialPriorRollPitchZ
— Type.mutable struct PartialPriorRollPitchZ{T1, T2} <: FunctorSingleton
Partial prior belief on Roll Pitch and Z of a Pose3
variable.
RoME.PartialPose3XYYaw
— Type.mutable struct PartialPose3XYYaw{T1, T2} <: FunctorPairwise
Partial factor between XY and Yaw of two Pose3 variables.
To be deprecated: use Pose3Pose3XYYaw instead.
RoME.Pose3Pose3XYYaw
— Type.mutable struct Pose3Pose3XYYaw{T1, T2} <: FunctorPairwise
Partial factor between XY and Yaw of two Pose3 variables.
Defaults in IncrementalInference.jl:
struct LinearConditional{T} <: FunctorPairwise
Default linear offset between two scalar variables.
struct MixtureLinearConditional{T} <: FunctorPairwise
Define a categorical mixture of (relative) likelihood beliefs between any two variables.
Extending Caesar with New Variables and Factors
A question that frequently arises is how to design custom variables and factors to solve a specific type of graph. One strength of Caesar is the ability to incorporate new variables and factors at will. Please refer to Adding Factors for more information on creating your own factors.