template struct mola::index_se3_t

Overview

Discrete index type for SE(3) lattices, suitable for std::map and std::unordered_map. The SO(3) part is parameterized as yaw/pitch/roll angles.

#include <index_se3_t.h>

template <typename cell_coord_t = int32_t>
struct index_se3_t
{
    // fields

    cell_coord_t cx = 0;
    cell_coord_t cy = 0;
    cell_coord_t cz = 0;
    cell_coord_t cyaw = 0;
    cell_coord_t cpitch = 0;
    cell_coord_t croll = 0;

    // construction

    index_se3_t();

    index_se3_t(
        cell_coord_t Cx,
        cell_coord_t Cy,
        cell_coord_t Cz,
        cell_coord_t Cyaw,
        cell_coord_t Cpitch,
        cell_coord_t Croll
        );

    // methods

    bool operator == (const index_se3_t<cell_coord_t>& o) const;
    bool operator != (const index_se3_t<cell_coord_t>& o) const;
};