Skip to content
Open
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
6 changes: 6 additions & 0 deletions nav2_ros_common/include/nav2_ros_common/validate_messages.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,8 @@ bool validateMsg(const double & num)
return true;
}

const double MAX_COVARIANCE = 1e6;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You could keep a minimum, these do have to be positive valued. So you can check if the element is < 0.0. That would be the most complete solution to your needs


template<size_t N>
bool validateMsg(const std::array<double, N> & msg)
{
Expand All @@ -65,6 +67,10 @@ bool validateMsg(const std::array<double, N> & msg)
*/
for (const auto & element : msg) {
if (!validateMsg(element)) {return false;}

if (std::abs(element) > MAX_COVARIANCE && element < 0.0) {
return false;
}
}

return true;
Expand Down
38 changes: 38 additions & 0 deletions nav2_ros_common/test/test_validation_messages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -320,6 +320,44 @@ TEST(ValidateMessagesTest, PoseWithCovarianceCheck) {
invalidate_msg2.pose.orientation.w = -0.32979028309372299;

EXPECT_FALSE(nav2::validateMsg(invalidate_msg2));

// Test over MAX value PoseWithCovariance message
geometry_msgs::msg::PoseWithCovariance invalidate_msg3;

invalidate_msg3.covariance[0] = 2e9; // > MAX_COVARIANCE (1e9)
for (size_t i = 1; i < invalidate_msg3.covariance.size(); ++i) {
invalidate_msg3.covariance[i] = 0.01; // Valid value
}

invalidate_msg3.pose.position.x = 0.0;
invalidate_msg3.pose.position.y = 0.0;
invalidate_msg3.pose.position.z = 0.0;

invalidate_msg3.pose.orientation.x = 0.0;
invalidate_msg3.pose.orientation.y = 0.0;
invalidate_msg3.pose.orientation.z = 0.0;
invalidate_msg3.pose.orientation.w = 1.0;

EXPECT_FALSE(nav2::validateMsg(invalidate_msg3));

// Test below MIN value PoseWithCovariance message
geometry_msgs::msg::PoseWithCovariance invalidate_msg4;

invalidate_msg4.covariance[0] = 1e-5; // < MIN_COVARIANCE (1e-4)
for (size_t i = 1; i < invalidate_msg4.covariance.size(); ++i) {
invalidate_msg4.covariance[i] = 0.01; // Valid value
}

invalidate_msg4.pose.position.x = 0.0;
invalidate_msg4.pose.position.y = 0.0;
invalidate_msg4.pose.position.z = 0.0;

invalidate_msg4.pose.orientation.x = 0.0;
invalidate_msg4.pose.orientation.y = 0.0;
invalidate_msg4.pose.orientation.z = 0.0;
invalidate_msg4.pose.orientation.w = 1.0;

EXPECT_FALSE(nav2::validateMsg(invalidate_msg4));
}

TEST(ValidateMessagesTest, PoseWithCovarianceStampedCheck) {
Expand Down
Loading