Skip to content
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

Add MANIF_ASSERT #138

Merged
merged 2 commits into from
Jun 17, 2020
Merged
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
21 changes: 21 additions & 0 deletions include/manif/impl/macro.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,12 @@

#include <stdexcept> // for std::runtime_error

#ifdef NDEBUG
# ifndef MANIF_NO_DEBUG
# define MANIF_NO_DEBUG
# endif
#endif

namespace manif {

struct runtime_error : std::runtime_error
Expand Down Expand Up @@ -73,6 +79,21 @@ raise(Args&&... args)
__MANIF_CHECK_MSG, \
__MANIF_CHECK)(__VA_ARGS__) )

// Assertions cost run time and can be turned off.
// You can suppress MANIF_ASSERT by defining
// MANIF_NO_DEBUG before including manif headers.
// MANIF_NO_DEBUG is undefined by default unless NDEBUG is defined.
#ifndef MANIF_NO_DEBUG
#define MANIF_ASSERT(...) \
__MANIF_EXPAND( \
__MANIF_GET_MACRO_3(__VA_ARGS__, \
__MANIF_CHECK_MSG_EXCEPT, \
__MANIF_CHECK_MSG, \
__MANIF_CHECK)(__VA_ARGS__) )
#else
#define MANIF_ASSERT(...) ((void)0)
#endif

#define MANIF_NOT_IMPLEMENTED_YET \
MANIF_THROW("Not implemented yet !");

Expand Down
8 changes: 4 additions & 4 deletions include/manif/impl/se2/SE2.h
Original file line number Diff line number Diff line change
Expand Up @@ -159,10 +159,10 @@ SE2<_Scalar>::SE2(const Eigen::MatrixBase<_EigenDerived>& data)
: data_(data)
{
using std::abs;
MANIF_CHECK(abs(data_.template tail<2>().norm()-Scalar(1)) <
Constants<Scalar>::eps_s,
"SE2 constructor argument not normalized !",
invalid_argument);
MANIF_ASSERT(abs(data_.template tail<2>().norm()-Scalar(1)) <
Constants<Scalar>::eps_s,
"SE2 constructor argument not normalized !",
invalid_argument);
}

template <typename _Scalar>
Expand Down
8 changes: 4 additions & 4 deletions include/manif/impl/se3/SE3.h
Original file line number Diff line number Diff line change
Expand Up @@ -157,10 +157,10 @@ SE3<_Scalar>::SE3(const Eigen::MatrixBase<_EigenDerived>& data)
: data_(data)
{
using std::abs;
MANIF_CHECK(abs(data_.template tail<4>().norm()-Scalar(1)) <
Constants<Scalar>::eps_s,
"SE3 constructor argument not normalized !",
invalid_argument);
MANIF_ASSERT(abs(data_.template tail<4>().norm()-Scalar(1)) <
Constants<Scalar>::eps_s,
"SE3 constructor argument not normalized !",
invalid_argument);
}

template <typename _Scalar>
Expand Down
6 changes: 3 additions & 3 deletions include/manif/impl/so2/SO2.h
Original file line number Diff line number Diff line change
Expand Up @@ -116,9 +116,9 @@ SO2<_Scalar>::SO2(const Eigen::MatrixBase<_EigenDerived>& data)
: data_(data)
{
using std::abs;
MANIF_CHECK(abs(data_.norm()-Scalar(1)) < Constants<Scalar>::eps_s,
"SO2 constructor argument not normalized !",
invalid_argument);
MANIF_ASSERT(abs(data_.norm()-Scalar(1)) < Constants<Scalar>::eps_s,
"SO2 constructor argument not normalized !",
invalid_argument);
}

template <typename _Scalar>
Expand Down
6 changes: 3 additions & 3 deletions include/manif/impl/so3/SO3.h
Original file line number Diff line number Diff line change
Expand Up @@ -131,9 +131,9 @@ SO3<_Scalar>::SO3(const Eigen::MatrixBase<_EigenDerived>& data)
: data_(data)
{
using std::abs;
MANIF_CHECK(abs(data_.norm()-Scalar(1)) < Constants<Scalar>::eps_s,
"SO3 constructor argument not normalized !",
invalid_argument);
MANIF_ASSERT(abs(data_.norm()-Scalar(1)) < Constants<Scalar>::eps_s,
"SO3 constructor argument not normalized !",
invalid_argument);
}

template <typename _Scalar>
Expand Down
42 changes: 23 additions & 19 deletions test/se2/gtest_se2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,25 +84,6 @@ TEST(TEST_SE2, TEST_SE2_CONSTRUCTOR_COPY)
EXPECT_DOUBLE_EQ(MANIF_PI/4., se2.angle());
}

TEST(TEST_SE2, TEST_SE2_CONSTRUCTOR_NOT_NORMALIZED_ARGS)
{
EXPECT_THROW(
SE2d se2(SE2d(4, 2, 1, 1)),
manif::invalid_argument
);

EXPECT_THROW(
SE2d se2(SE2d::DataType(4, 2, 1, 1)),
manif::invalid_argument
);

try {
SE2d se2(SE2d::DataType(4, 2, 1, 1));
} catch (manif::invalid_argument& e) {
EXPECT_FALSE(std::string(e.what()).empty());
}
}

TEST(TEST_SE2, TEST_SE2_COEFFS)
{
SE2d se2(4, 2, 0);
Expand Down Expand Up @@ -523,6 +504,27 @@ TEST(TEST_SE2, TEST_SE2_ACT)
EXPECT_NEAR(1, transformed_point.y(), 1e-15);
}

#ifndef MANIF_NO_DEBUG

TEST(TEST_SE2, TEST_SE2_CONSTRUCTOR_NOT_NORMALIZED_ARGS)
{
EXPECT_THROW(
SE2d se2(SE2d(4, 2, 1, 1)),
manif::invalid_argument
);

EXPECT_THROW(
SE2d se2(SE2d::DataType(4, 2, 1, 1)),
manif::invalid_argument
);

try {
SE2d se2(SE2d::DataType(4, 2, 1, 1));
} catch (manif::invalid_argument& e) {
EXPECT_FALSE(std::string(e.what()).empty());
}
}

TEST(TEST_SE2, TEST_SE2_CONSTRUCTOR_UNNORMALIZED)
{
using DataType = typename SE2d::DataType;
Expand All @@ -548,6 +550,8 @@ TEST(TEST_SE2, TEST_SE2_NORMALIZE)
);
}

#endif

MANIF_TEST(SE2d);

MANIF_TEST_MAP(SE2d);
Expand Down
46 changes: 25 additions & 21 deletions test/se3/gtest_se3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,27 +82,6 @@ TEST(TEST_SE3, TEST_SE3_CONSTRUCTOR_COPY)
EXPECT_DOUBLE_EQ(1, se3.coeffs()(6));
}

TEST(TEST_SE3, TEST_SE3_CONSTRUCTOR_NOT_NORMALIZED_ARGS)
{
// EXPECT_THROW(
// SE3d se3(SE3d(1, 1)),
// manif::invalid_argument
// );

SE3d::DataType values; values << 0,0,0, 1,1,1,1;

EXPECT_THROW(
SE3d se3(values),
manif::invalid_argument
);

try {
SE3d se3(values);
} catch (manif::invalid_argument& e) {
EXPECT_FALSE(std::string(e.what()).empty());
}
}

TEST(TEST_SE3, TEST_SE3_DATA)
{
SE3d::DataType values; values << 0,0,0, 0,0,0,1;
Expand Down Expand Up @@ -353,6 +332,29 @@ TEST(TEST_SE3, TEST_SE3_ISOMETRY)
EXPECT_DOUBLE_EQ(3, se3h.matrix()(2,3));
}

#ifndef MANIF_NO_DEBUG

TEST(TEST_SE3, TEST_SE3_CONSTRUCTOR_NOT_NORMALIZED_ARGS)
{
// EXPECT_THROW(
// SE3d se3(SE3d(1, 1)),
// manif::invalid_argument
// );

SE3d::DataType values; values << 0,0,0, 1,1,1,1;

EXPECT_THROW(
SE3d se3(values),
manif::invalid_argument
);

try {
SE3d se3(values);
} catch (manif::invalid_argument& e) {
EXPECT_FALSE(std::string(e.what()).empty());
}
}

TEST(TEST_SE3, TEST_SE3_CONSTRUCTOR_UNNORMALIZED)
{
using DataType = typename SE3d::DataType;
Expand All @@ -378,6 +380,8 @@ TEST(TEST_SE3, TEST_SE3_NORMALIZE)
);
}

#endif

MANIF_TEST(SE3d);

MANIF_TEST_MAP(SE3d);
Expand Down
42 changes: 23 additions & 19 deletions test/so2/gtest_so2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,25 +42,6 @@ TEST(TEST_SO2, TEST_SO2_CONSTRUCTOR_COPY)
EXPECT_DOUBLE_EQ(MANIF_PI/4., so2.angle());
}

TEST(TEST_SO2, TEST_SO2_CONSTRUCTOR_NOT_NORMALIZED_ARGS)
{
EXPECT_THROW(
SO2d so2(SO2d(1, 1)),
manif::invalid_argument
);

EXPECT_THROW(
SO2d so2(SO2d::DataType(1, 1)),
manif::invalid_argument
);

try {
SO2d so2(SO2d::DataType(1, 1));
} catch (manif::invalid_argument& e) {
EXPECT_FALSE(std::string(e.what()).empty());
}
}

TEST(TEST_SO2, TEST_SO2_COEFFS)
{
SO2d so2(0);
Expand Down Expand Up @@ -551,6 +532,27 @@ TEST(TEST_SO2, TEST_SO2_ACT)
EXPECT_NEAR(+1, transformed_point.y(), 1e-15);
}

#ifndef MANIF_NO_DEBUG

TEST(TEST_SO2, TEST_SO2_CONSTRUCTOR_NOT_NORMALIZED_ARGS)
{
EXPECT_THROW(
SO2d so2(SO2d(1, 1)),
manif::invalid_argument
);

EXPECT_THROW(
SO2d so2(SO2d::DataType(1, 1)),
manif::invalid_argument
);

try {
SO2d so2(SO2d::DataType(1, 1));
} catch (manif::invalid_argument& e) {
EXPECT_FALSE(std::string(e.what()).empty());
}
}

TEST(TEST_SO2, TEST_SO2_CONSTRUCTOR_UNNORMALIZED)
{
using DataType = typename SO2d::DataType;
Expand All @@ -576,6 +578,8 @@ TEST(TEST_SO2, TEST_SO2_NORMALIZE)
);
}

#endif

MANIF_TEST(SO2d);

MANIF_TEST_MAP(SO2d);
Expand Down
42 changes: 23 additions & 19 deletions test/so3/gtest_so3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,25 +56,6 @@ TEST(TEST_SO3, TEST_SO3_CONSTRUCTOR_ROLL_PITCH_YAW)
EXPECT_DOUBLE_EQ(1, so3.w());
}

TEST(TEST_SO3, TEST_SO3_CONSTRUCTOR_NOT_NORMALIZED_ARGS)
{
EXPECT_THROW(
SO3d so3(SO3d(1, 1, 1, 1)),
manif::invalid_argument
);

EXPECT_THROW(
SO3d so3(SO3d::DataType(1, 1, 1, 1)),
manif::invalid_argument
);

try {
SO3d so3(SO3d::DataType(1, 1, 1, 1));
} catch (manif::invalid_argument& e) {
EXPECT_FALSE(std::string(e.what()).empty());
}
}

TEST(TEST_SO3, TEST_SO3_IDENTITY)
{
SO3d so3;
Expand Down Expand Up @@ -566,6 +547,27 @@ TEST(TEST_SO3, TEST_SO3_ACT)
EXPECT_NEAR( 1, transformed_point.z(), 1e-15);
}

#ifndef MANIF_NO_DEBUG

TEST(TEST_SO3, TEST_SO3_CONSTRUCTOR_NOT_NORMALIZED_ARGS)
{
EXPECT_THROW(
SO3d so3(SO3d(1, 1, 1, 1)),
manif::invalid_argument
);

EXPECT_THROW(
SO3d so3(SO3d::DataType(1, 1, 1, 1)),
manif::invalid_argument
);

try {
SO3d so3(SO3d::DataType(1, 1, 1, 1));
} catch (manif::invalid_argument& e) {
EXPECT_FALSE(std::string(e.what()).empty());
}
}

TEST(TEST_SO3, TEST_SO3_CONSTRUCTOR_UNNORMALIZED)
{
using DataType = typename SO3d::DataType;
Expand All @@ -591,6 +593,8 @@ TEST(TEST_SO3, TEST_SO3_NORMALIZE)
);
}

#endif

MANIF_TEST(SO3d);

MANIF_TEST_MAP(SO3d);
Expand Down