Skip to content

Adding doc and tests #1492

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Draft
wants to merge 7 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 3 additions & 6 deletions .github/workflows/cmake.yml
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,6 @@ jobs:
run: |
./rtabmap-console --version

# - name: Test
# working-directory: ${{github.workspace}}/build
# # Execute tests defined by the CMake configuration.
# # See https://cmake.org/cmake/help/latest/manual/ctest.1.html for more detail
# run: ctest -C ${{env.BUILD_TYPE}}

- name: Test
working-directory: ${{github.workspace}}/build
run: ctest -C ${{env.BUILD_TYPE}} --output-on-failure
18 changes: 18 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -166,6 +166,23 @@ OPTION(BUILD_APP "Build main application" ON)
OPTION(BUILD_TOOLS "Build tools" ON)
OPTION(BUILD_EXAMPLES "Build examples" ON)

include(CTest)
if(BUILD_TESTING)
# Add GTest using FetchContent
include(FetchContent)
FetchContent_Declare(
googletest
URL https://github.com/google/googletest/archive/refs/tags/v1.16.0.zip
)
FetchContent_GetProperties(googletest)
if(NOT googletest_POPULATED)
FetchContent_Populate(googletest)
add_subdirectory(${googletest_SOURCE_DIR} ${googletest_BINARY_DIR})
endif()
include(GoogleTest)
set(TEST_DATA_ROOT "${CMAKE_CURRENT_SOURCE_DIR}/data")
endif()

####### DEPENDENCIES #######
IF(MOBILE_BUILD)
option(WITH_QT "Include Qt support" OFF)
Expand Down Expand Up @@ -1333,6 +1350,7 @@ MESSAGE(STATUS " CMAKE_INSTALL_LIBDIR = ${CMAKE_INSTALL_LIBDIR}")
MESSAGE(STATUS " BUILD_APP = ${BUILD_APP}")
MESSAGE(STATUS " BUILD_TOOLS = ${BUILD_TOOLS}")
MESSAGE(STATUS " BUILD_EXAMPLES = ${BUILD_EXAMPLES}")
MESSAGE(STATUS " BUILD_TESTING = ${BUILD_TESTING}")
IF(NOT WIN32)
# see comment above for the BUILD_SHARED_LIBS option on Windows
MESSAGE(STATUS " BUILD_SHARED_LIBS = ${BUILD_SHARED_LIBS}")
Expand Down
2,604 changes: 2,604 additions & 0 deletions Doxyfile

Large diffs are not rendered by default.

6 changes: 5 additions & 1 deletion corelib/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1 +1,5 @@
ADD_SUBDIRECTORY( src )
ADD_SUBDIRECTORY( src )

if(BUILD_TESTING)
ADD_SUBDIRECTORY( test )
endif()
109 changes: 82 additions & 27 deletions corelib/include/rtabmap/core/LaserScan.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,34 +34,63 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

namespace rtabmap {

/**
* @class LaserScan
* @brief Represents 2D or 3D laser scan data with support for multiple point data formats.
*
* The LaserScan class stores structured laser scan data used in SLAM, mapping, and perception.
* It supports various formats including point coordinates, intensity, normals, RGB colors,
* and timestamps. Utility methods are provided for format checking, cloning, and combining scans.
*/
class RTABMAP_CORE_EXPORT LaserScan
{
public:
enum Format{kUnknown=0,
kXY=1,
kXYI=2,
kXYNormal=3,
kXYINormal=4,
kXYZ=5,
kXYZI=6,
kXYZRGB=7,
kXYZNormal=8,
kXYZINormal=9,
kXYZRGBNormal=10,
kXYZIT=11};

/**
* @brief Enumeration of possible formats for laser scan data.
*
* These values represent different combinations of point attributes
* that can be stored in a laser scan. The format determines how each
* point in the scan is structured.
*/
enum Format{
kUnknown=0, /**< Unknown format. */
kXY=1, /**< 2D points with X and Y coordinates. */
kXYI=2, /**< 2D points with X, Y and intensity. */
kXYNormal=3, /**< 2D points with X, Y and normal vectors. */
kXYINormal=4, /**< 2D points with X, Y, intensity and normal vectors. */
kXYZ=5, /**< 3D points with X, Y and Z coordinates. */
kXYZI=6, /**< 3D points with X, Y, Z and intensity. */
kXYZRGB=7, /**< 3D points with X, Y, Z and RGB color. */
kXYZNormal=8, /**< 3D points with X, Y, Z and normal vectors. */
kXYZINormal=9, /**< 3D points with X, Y, Z, intensity and normal vectors. */
kXYZRGBNormal=10, /**< 3D points with X, Y, Z, RGB color and normal vectors. */
kXYZIT=11 /**< 3D points with X, Y, Z, intensity and time. */
};

/// @name Static Utility Functions
/// @{
static std::string formatName(const Format & format);
static int channels(const Format & format);
static bool isScan2d(const Format & format);
static bool isScanHasNormals(const Format & format);
static bool isScanHasRGB(const Format & format);
static bool isScanHasIntensity(const Format & format);
static bool isScanHasTime(const Format & format);
static float packRGB(unsigned char r, unsigned char g, unsigned char b);
static void unpackRGB(float rgb, unsigned char & r, unsigned char & g, unsigned char & b);

/**
* @brief Converts legacy scan format to a LaserScan object.
*/
static LaserScan backwardCompatibility(
const cv::Mat & oldScanFormat,
int maxPoints = 0,
int maxRange = 0,
const Transform & localTransform = Transform::getIdentity());

/**
* @brief Converts legacy scan format with additional metadata to a LaserScan.
*/
static LaserScan backwardCompatibility(
const cv::Mat & oldScanFormat,
float minRange,
Expand All @@ -70,14 +99,19 @@ class RTABMAP_CORE_EXPORT LaserScan
float angleMax,
float angleInc,
const Transform & localTransform = Transform::getIdentity());
/// @}

public:

/// @name Constructors
/// @{
LaserScan();
LaserScan(const LaserScan & data,
int maxPoints,
float maxRange,
const Transform & localTransform = Transform::getIdentity());
// Use version without \"format\" argument.

/// @deprecated Use constructor without `format` argument.
RTABMAP_DEPRECATED LaserScan(const LaserScan & data,
int maxPoints,
float maxRange,
Expand All @@ -88,7 +122,8 @@ class RTABMAP_CORE_EXPORT LaserScan
float maxRange,
Format format,
const Transform & localTransform = Transform::getIdentity());
// Use version without \"format\" argument.

/// @deprecated Use constructor without `format` argument.
RTABMAP_DEPRECATED LaserScan(const LaserScan & data,
Format format,
float minRange,
Expand All @@ -112,7 +147,10 @@ class RTABMAP_CORE_EXPORT LaserScan
float angleMax,
float angleIncrement,
const Transform & localTransform = Transform::getIdentity());
/// @}

/// @name Accessors
/// @{
const cv::Mat & data() const {return data_;}
Format format() const {return format_;}
std::string formatName() const {return formatName(format_);}
Expand All @@ -125,7 +163,10 @@ class RTABMAP_CORE_EXPORT LaserScan
float angleIncrement() const {return angleIncrement_;}
void setLocalTransform(const Transform & t) {localTransform_ = t;}
Transform localTransform() const {return localTransform_;}
/// @}

/// @name Status and Format Checks
/// @{
bool empty() const {return data_.empty();}
bool isEmpty() const {return data_.empty();}
int size() const {return data_.total();}
Expand All @@ -139,24 +180,38 @@ class RTABMAP_CORE_EXPORT LaserScan
bool isOrganized() const {return data_.rows > 1;}
LaserScan clone() const;
LaserScan densify() const;
/// @}

/// @name Operations
/// @{
int getIntensityOffset() const {return hasIntensity()?(is2d()?2:3):-1;}
int getRGBOffset() const {return hasRGB()?(is2d()?2:3):-1;}
int getNormalsOffset() const {return hasNormals()?(2 + (is2d()?0:1) + ((hasRGB() || hasIntensity())?1:0)):-1;}
int getTimeOffset() const {return hasTime()?4:-1;}

/**
* @brief Access a specific field value of a point.
* @param pointIndex Index of the point.
* @param channelOffset Channel offset to access (e.g., 0=X, 1=Y, 2=Z if 2D, for other fields, use corresponding getter functions).
* @return Reference to the field value.
* @see getIntensityOffset() getRGBOffset() getNormalsOffset() getTimeOffset()
*/
float & field(unsigned int pointIndex, unsigned int channelOffset);

/**
* @brief Clear the scan data.
*/
void clear() {data_ = cv::Mat();}

/**
* Concatenate scan's data, localTransform is ignored.
* @brief Concatenate scan's data (localTransform is ignored).
*/
LaserScan & operator+=(const LaserScan &);
/**
* Concatenate scan's data, localTransform is ignored.
* @brief Concatenate scan's data (localTransform is ignored).
*/
LaserScan operator+(const LaserScan &);
/// @}

private:
void init(const cv::Mat & data,
Expand All @@ -170,17 +225,17 @@ class RTABMAP_CORE_EXPORT LaserScan
const Transform & localTransform = Transform::getIdentity());

private:
cv::Mat data_;
Format format_;
int maxPoints_;
float rangeMin_;
float rangeMax_;
float angleMin_;
float angleMax_;
float angleIncrement_;
Transform localTransform_;
cv::Mat data_; ///< The scan data matrix.
Format format_; ///< The scan data format.
int maxPoints_; ///< Maximum number of points allowed.
float rangeMin_; ///< Minimum valid range.
float rangeMax_; ///< Maximum valid range.
float angleMin_; ///< Minimum angle (for 2D scans).
float angleMax_; ///< Maximum angle (for 2D scans).
float angleIncrement_; ///< Angular increment (for 2D scans).
Transform localTransform_; ///< Transform from base frame to scan frame.
};

}
} // namespace rtabmap

#endif /* CORELIB_INCLUDE_RTABMAP_CORE_LASERSCAN_H_ */
4 changes: 3 additions & 1 deletion corelib/include/rtabmap/core/camera/CameraOpenni.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,9 @@ class Grabber;

namespace rtabmap
{

/**
* @brief OpenNI driver for cameras like Kinect for Xbox 360
*/
class RTABMAP_CORE_EXPORT CameraOpenni :
public Camera
{
Expand Down
Loading
Loading