Skip to content

Commit

Permalink
reformat
Browse files Browse the repository at this point in the history
Signed-off-by: goes <[email protected]>
  • Loading branch information
goes authored and goes committed May 6, 2024
1 parent 27d42a0 commit b3e8d55
Show file tree
Hide file tree
Showing 2 changed files with 95 additions and 96 deletions.
19 changes: 9 additions & 10 deletions nav2_util/include/nav2_util/validate_messages.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,11 +56,11 @@ bool validateMsg(const double & num)
}

template<size_t N>
bool validateMsg(const std::array<double, N>& msg) {
bool validateMsg(const std::array<double, N> & msg)
{
// @brief double-array value check
for (const auto& element : msg)
{
if(!validateMsg(element)) {return false;}
for (const auto & element : msg) {
if (!validateMsg(element)) {return false;}
}

return true;
Expand Down Expand Up @@ -125,22 +125,21 @@ bool validateMsg(const geometry_msgs::msg::Pose & msg)
bool validateMsg(const geometry_msgs::msg::PoseWithCovariance & msg)
{
// check sub-type
if(!validateMsg(msg.pose)) {return false;}
if(!validateMsg(msg.covariance)) {return false;}
if (!validateMsg(msg.pose)) {return false;}
if (!validateMsg(msg.covariance)) {return false;}

return true;
}

bool validateMsg(const geometry_msgs::msg::PoseWithCovarianceStamped & msg)
{
// check sub-type
if(!validateMsg(msg.header)) {return false;}
if(!validateMsg(msg.pose)) {return false;}
if (!validateMsg(msg.header)) {return false;}
if (!validateMsg(msg.pose)) {return false;}
return true;
}



// Function to verify map meta information
bool validateMsg(const nav_msgs::msg::MapMetaData & msg)
{
Expand Down
172 changes: 86 additions & 86 deletions nav2_util/test/test_validation_messages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -244,138 +244,138 @@ TEST(ValidateMessagesTest, OccupancyGridCheck) {
EXPECT_FALSE(nav2_util::validateMsg(invalid_occupancy_grid));
}

TEST(ValidateMessagesTest, PoseWithCovarianceCheck){
TEST(ValidateMessagesTest, PoseWithCovarianceCheck) {
geometry_msgs::msg::PoseWithCovariance validate_msg = {
// covariance
{0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
// pose
{
// position
{0.50010401010515571, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
// position
{0.50010401010515571, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
}
};
EXPECT_TRUE(nav2_util::validateMsg(validate_msg));

geometry_msgs::msg::PoseWithCovariance
invalidate_msg = {
geometry_msgs::msg::PoseWithCovariance
invalidate_msg = {
// covariance
{0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, NAN, 0.0, NAN, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
// pose
{
// position
{0.50010401010515571, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
// position
{0.50010401010515571, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
}
};
EXPECT_FALSE(nav2_util::validateMsg(invalidate_msg));

invalidate_msg = {
// covariance
{0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
// pose
{
// position
{NAN, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
// position
{NAN, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
}
};
EXPECT_FALSE(nav2_util::validateMsg(invalidate_msg));
}


TEST(ValidateMessagesTest, PoseWithCovarianceStampedCheck){
TEST(ValidateMessagesTest, PoseWithCovarianceStampedCheck) {
geometry_msgs::msg::PoseWithCovarianceStamped validate_msg = {
// Header
// Header
{
// frame_id
"map",
// stamp
{
// frame_id
"map",
// stamp
{
1711029956, // sec
146734875 // nanosec
}
},
// Pose
1711029956, // sec
146734875 // nanosec
}
},
// Pose
{
// covariance
{0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
// pose
{
// covariance
{0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
// pose
{
// position
{0.50010401010515571, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
}
// position
{0.50010401010515571, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
}
}
};
EXPECT_TRUE(nav2_util::validateMsg(validate_msg));

geometry_msgs::msg::PoseWithCovarianceStamped
invalidate_msg = {
// Header
invalidate_msg = {
// Header
{
// frame_id
"map",
// stamp
{
// frame_id
"map",
// stamp
{
1711029956, // sec
146734875 // nanosec
}
},
// Pose
1711029956, // sec
146734875 // nanosec
}
},
// Pose
{
// covariance
{0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, NAN, 0.0, NAN, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
// pose
{
// covariance
{0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, NAN, 0.0, NAN, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
// pose
{
// position
{0.50010401010515571, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
}
// position
{0.50010401010515571, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
}
}
};
EXPECT_FALSE(nav2_util::validateMsg(invalidate_msg));

invalidate_msg = {
// Header
// Header
{
// frame_id
"",
// stamp
{
// frame_id
"",
// stamp
{
1711029956, // sec
146734875 // nanosec
}
},
// Pose
1711029956, // sec
146734875 // nanosec
}
},
// Pose
{
// covariance
{0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
// pose
{
// covariance
{0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467},
// pose
{
// position
{0.50010401010515571, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
}
// position
{0.50010401010515571, 1.7468730211257935, 0.0},
// orientation
{0.9440542194053062, 0.0, 0.0, -0.32979028309372299}
}
}
};
EXPECT_FALSE(nav2_util::validateMsg(invalidate_msg));
}
Expand Down

0 comments on commit b3e8d55

Please sign in to comment.