sba/Frame Message

File: sba/Frame.msg

# New Frame
Header header

# New nodes (generally just 1, but want to leave this open)
CameraNode[] nodes

# New points added from the frame
WorldPoint[] points

# New projections
Projection[] projections

Expanded Definition

Header header
    uint32 seq
    time stamp
    string frame_id
CameraNode[] nodes
    uint32 index
    geometry_msgs/Transform transform
        geometry_msgs/Vector3 translation
            float64 x
            float64 y
            float64 z
        geometry_msgs/Quaternion rotation
            float64 x
            float64 y
            float64 z
            float64 w
    float64 fx
    float64 fy
    float64 cx
    float64 cy
    float64 baseline
    bool fixed
WorldPoint[] points
    uint32 index
    float64 x
    float64 y
    float64 z
    float64 w
Projection[] projections
    uint32 camindex
    uint32 pointindex
    float64 u
    float64 v
    float64 d
    bool stereo
    bool usecovariance
    float64[9] covariance