Skip to content

Commit e7df24d

Browse files
committed
Adding nan twist rejection for velocity smoother and collision monitor (#3658)
* adding nan twist rejection for velocity smoother and collision monitor * deref
1 parent 083e20c commit e7df24d

File tree

7 files changed

+80
-0
lines changed

7 files changed

+80
-0
lines changed

nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,8 @@
2727
#include "tf2_ros/transform_listener.h"
2828

2929
#include "nav2_util/lifecycle_node.hpp"
30+
#include "nav2_util/robot_utils.hpp"
31+
#include "nav2_msgs/msg/collision_monitor_state.hpp"
3032

3133
#include "nav2_collision_monitor/types.hpp"
3234
#include "nav2_collision_monitor/polygon.hpp"

nav2_collision_monitor/src/collision_monitor_node.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -148,6 +148,12 @@ CollisionMonitor::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
148148

149149
void CollisionMonitor::cmdVelInCallback(geometry_msgs::msg::Twist::ConstSharedPtr msg)
150150
{
151+
// If message contains NaN or Inf, ignore
152+
if (!nav2_util::validateTwist(*msg)) {
153+
RCLCPP_ERROR(get_logger(), "Velocity message contains NaNs or Infs! Ignoring as invalid!");
154+
return;
155+
}
156+
151157
process({msg->linear.x, msg->linear.y, msg->angular.z});
152158
}
153159

nav2_util/include/nav2_util/robot_utils.hpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@
2020
#include <string>
2121

2222
#include "geometry_msgs/msg/pose_stamped.hpp"
23+
#include "geometry_msgs/msg/twist.hpp"
24+
#include "tf2/time.h"
2325
#include "tf2_ros/buffer.h"
2426
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
2527
#include "rclcpp/rclcpp.hpp"
@@ -107,6 +109,13 @@ bool getTransform(
107109
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
108110
tf2::Transform & tf2_transform);
109111

112+
/**
113+
* @brief Validates a twist message contains no nans or infs
114+
* @param msg Twist message to validate
115+
* @return True if valid, false if contains unactionable values
116+
*/
117+
bool validateTwist(const geometry_msgs::msg::Twist & msg);
118+
110119
} // end namespace nav2_util
111120

112121
#endif // NAV2_UTIL__ROBOT_UTILS_HPP_

nav2_util/src/robot_utils.cpp

Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
// limitations under the License.
1616

1717
#include <string>
18+
#include <cmath>
1819
#include <memory>
1920

2021
#include "nav2_util/robot_utils.hpp"
@@ -141,4 +142,33 @@ bool getTransform(
141142
return true;
142143
}
143144

145+
bool validateTwist(const geometry_msgs::msg::Twist & msg)
146+
{
147+
if (std::isinf(msg.linear.x) || std::isnan(msg.linear.x)) {
148+
return false;
149+
}
150+
151+
if (std::isinf(msg.linear.y) || std::isnan(msg.linear.y)) {
152+
return false;
153+
}
154+
155+
if (std::isinf(msg.linear.z) || std::isnan(msg.linear.z)) {
156+
return false;
157+
}
158+
159+
if (std::isinf(msg.angular.x) || std::isnan(msg.angular.x)) {
160+
return false;
161+
}
162+
163+
if (std::isinf(msg.angular.y) || std::isnan(msg.angular.y)) {
164+
return false;
165+
}
166+
167+
if (std::isinf(msg.angular.z) || std::isnan(msg.angular.z)) {
168+
return false;
169+
}
170+
171+
return true;
172+
}
173+
144174
} // end namespace nav2_util

nav2_util/test/test_robot_utils.cpp

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
// limitations under the License.
1414

1515
#include <memory>
16+
#include <cmath>
1617
#include "rclcpp/rclcpp.hpp"
1718
#include "nav2_util/robot_utils.hpp"
1819
#include "tf2_ros/transform_listener.h"
@@ -32,3 +33,28 @@ TEST(RobotUtils, LookupExceptionError)
3233
global_pose.header.frame_id = "base_link";
3334
ASSERT_FALSE(nav2_util::transformPoseInTargetFrame(global_pose, global_pose, tf, "map", 0.1));
3435
}
36+
37+
TEST(RobotUtils, validateTwist)
38+
{
39+
geometry_msgs::msg::Twist msg;
40+
EXPECT_TRUE(nav2_util::validateTwist(msg));
41+
42+
msg.linear.x = NAN;
43+
EXPECT_FALSE(nav2_util::validateTwist(msg));
44+
msg.linear.x = 1;
45+
msg.linear.y = NAN;
46+
EXPECT_FALSE(nav2_util::validateTwist(msg));
47+
msg.linear.y = 1;
48+
msg.linear.z = NAN;
49+
EXPECT_FALSE(nav2_util::validateTwist(msg));
50+
51+
msg.linear.z = 1;
52+
msg.angular.x = NAN;
53+
EXPECT_FALSE(nav2_util::validateTwist(msg));
54+
msg.angular.x = 1;
55+
msg.angular.y = NAN;
56+
EXPECT_FALSE(nav2_util::validateTwist(msg));
57+
msg.angular.y = 1;
58+
msg.angular.z = NAN;
59+
EXPECT_FALSE(nav2_util::validateTwist(msg));
60+
}

nav2_velocity_smoother/include/nav2_velocity_smoother/velocity_smoother.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include "nav2_util/lifecycle_node.hpp"
2626
#include "nav2_util/node_utils.hpp"
2727
#include "nav2_util/odometry_utils.hpp"
28+
#include "nav2_util/robot_utils.hpp"
2829

2930
namespace nav2_velocity_smoother
3031
{

nav2_velocity_smoother/src/velocity_smoother.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -174,6 +174,12 @@ VelocitySmoother::on_shutdown(const rclcpp_lifecycle::State &)
174174

175175
void VelocitySmoother::inputCommandCallback(const geometry_msgs::msg::Twist::SharedPtr msg)
176176
{
177+
// If message contains NaN or Inf, ignore
178+
if (!nav2_util::validateTwist(*msg)) {
179+
RCLCPP_ERROR(get_logger(), "Velocity message contains NaNs or Infs! Ignoring as invalid!");
180+
return;
181+
}
182+
177183
command_ = msg;
178184
last_command_time_ = now();
179185
}

0 commit comments

Comments
 (0)