Skip to content

Commit

Permalink
Adding nan twist rejection for velocity smoother and collision monitor (
Browse files Browse the repository at this point in the history
ros-navigation#3658)

* adding nan twist rejection for velocity smoother and collision monitor

* deref

Signed-off-by: enricosutera <enricosutera@outlook.com>
  • Loading branch information
SteveMacenski authored and enricosutera committed May 19, 2024
1 parent 763c26d commit 84b8a7b
Show file tree
Hide file tree
Showing 7 changed files with 78 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "tf2_ros/transform_listener.h"

#include "nav2_util/lifecycle_node.hpp"
#include "nav2_util/robot_utils.hpp"
#include "nav2_msgs/msg/collision_monitor_state.hpp"

#include "nav2_collision_monitor/types.hpp"
Expand Down
6 changes: 6 additions & 0 deletions nav2_collision_monitor/src/collision_monitor_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,6 +160,12 @@ CollisionMonitor::on_shutdown(const rclcpp_lifecycle::State & /*state*/)

void CollisionMonitor::cmdVelInCallback(geometry_msgs::msg::Twist::ConstSharedPtr msg)
{
// If message contains NaN or Inf, ignore
if (!nav2_util::validateTwist(*msg)) {
RCLCPP_ERROR(get_logger(), "Velocity message contains NaNs or Infs! Ignoring as invalid!");
return;
}

process({msg->linear.x, msg->linear.y, msg->angular.z});
}

Expand Down
8 changes: 8 additions & 0 deletions nav2_util/include/nav2_util/robot_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <memory>

#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "tf2/time.h"
#include "tf2_ros/buffer.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
Expand Down Expand Up @@ -109,6 +110,13 @@ bool getTransform(
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
tf2::Transform & tf2_transform);

/**
* @brief Validates a twist message contains no nans or infs
* @param msg Twist message to validate
* @return True if valid, false if contains unactionable values
*/
bool validateTwist(const geometry_msgs::msg::Twist & msg);

} // end namespace nav2_util

#endif // NAV2_UTIL__ROBOT_UTILS_HPP_
30 changes: 30 additions & 0 deletions nav2_util/src/robot_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
// limitations under the License.

#include <string>
#include <cmath>
#include <memory>

#include "tf2/convert.h"
Expand Down Expand Up @@ -142,4 +143,33 @@ bool getTransform(
return true;
}

bool validateTwist(const geometry_msgs::msg::Twist & msg)
{
if (std::isinf(msg.linear.x) || std::isnan(msg.linear.x)) {
return false;
}

if (std::isinf(msg.linear.y) || std::isnan(msg.linear.y)) {
return false;
}

if (std::isinf(msg.linear.z) || std::isnan(msg.linear.z)) {
return false;
}

if (std::isinf(msg.angular.x) || std::isnan(msg.angular.x)) {
return false;
}

if (std::isinf(msg.angular.y) || std::isnan(msg.angular.y)) {
return false;
}

if (std::isinf(msg.angular.z) || std::isnan(msg.angular.z)) {
return false;
}

return true;
}

} // end namespace nav2_util
26 changes: 26 additions & 0 deletions nav2_util/test/test_robot_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
// limitations under the License.

#include <memory>
#include <cmath>
#include "rclcpp/rclcpp.hpp"
#include "nav2_util/robot_utils.hpp"
#include "tf2_ros/transform_listener.h"
Expand All @@ -32,3 +33,28 @@ TEST(RobotUtils, LookupExceptionError)
global_pose.header.frame_id = "base_link";
ASSERT_FALSE(nav2_util::transformPoseInTargetFrame(global_pose, global_pose, tf, "map", 0.1));
}

TEST(RobotUtils, validateTwist)
{
geometry_msgs::msg::Twist msg;
EXPECT_TRUE(nav2_util::validateTwist(msg));

msg.linear.x = NAN;
EXPECT_FALSE(nav2_util::validateTwist(msg));
msg.linear.x = 1;
msg.linear.y = NAN;
EXPECT_FALSE(nav2_util::validateTwist(msg));
msg.linear.y = 1;
msg.linear.z = NAN;
EXPECT_FALSE(nav2_util::validateTwist(msg));

msg.linear.z = 1;
msg.angular.x = NAN;
EXPECT_FALSE(nav2_util::validateTwist(msg));
msg.angular.x = 1;
msg.angular.y = NAN;
EXPECT_FALSE(nav2_util::validateTwist(msg));
msg.angular.y = 1;
msg.angular.z = NAN;
EXPECT_FALSE(nav2_util::validateTwist(msg));
}
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/odometry_utils.hpp"
#include "nav2_util/robot_utils.hpp"

namespace nav2_velocity_smoother
{
Expand Down
6 changes: 6 additions & 0 deletions nav2_velocity_smoother/src/velocity_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,6 +174,12 @@ VelocitySmoother::on_shutdown(const rclcpp_lifecycle::State &)

void VelocitySmoother::inputCommandCallback(const geometry_msgs::msg::Twist::SharedPtr msg)
{
// If message contains NaN or Inf, ignore
if (!nav2_util::validateTwist(*msg)) {
RCLCPP_ERROR(get_logger(), "Velocity message contains NaNs or Infs! Ignoring as invalid!");
return;
}

command_ = msg;
last_command_time_ = now();
}
Expand Down

0 comments on commit 84b8a7b

Please sign in to comment.