Skip to content

Commit 3d43b6f

Browse files
urfeexmamueluth
authored andcommitted
[pose_broadcaster] Check for valid pose before attempting to publish a tf for it (ros-controls#1479)
1 parent 91f22d3 commit 3d43b6f

File tree

3 files changed

+86
-4
lines changed

3 files changed

+86
-4
lines changed

pose_broadcaster/src/pose_broadcaster.cpp

Lines changed: 24 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414
#include "pose_broadcaster/pose_broadcaster.hpp"
15+
#include <cmath>
16+
#include <rclcpp/logging.hpp>
1517

1618
namespace
1719
{
@@ -24,6 +26,19 @@ constexpr auto DEFAULT_TF_TOPIC = "/tf";
2426
namespace pose_broadcaster
2527
{
2628

29+
bool is_pose_valid(const geometry_msgs::msg::Pose & pose)
30+
{
31+
return std::isfinite(pose.position.x) && std::isfinite(pose.position.y) &&
32+
std::isfinite(pose.position.z) && std::isfinite(pose.orientation.x) &&
33+
std::isfinite(pose.orientation.y) && std::isfinite(pose.orientation.z) &&
34+
std::isfinite(pose.orientation.w) &&
35+
36+
std::abs(
37+
pose.orientation.x * pose.orientation.x + pose.orientation.y * pose.orientation.y +
38+
pose.orientation.z * pose.orientation.z + pose.orientation.w * pose.orientation.w -
39+
1.0) <= 10e-3;
40+
}
41+
2742
controller_interface::InterfaceConfiguration PoseBroadcaster::command_interface_configuration()
2843
const
2944
{
@@ -147,8 +162,15 @@ controller_interface::return_type PoseBroadcaster::update(
147162
realtime_publisher_->msg_.pose = pose;
148163
realtime_publisher_->unlockAndPublish();
149164
}
150-
151-
if (realtime_tf_publisher_ && realtime_tf_publisher_->trylock())
165+
if (!is_pose_valid(pose))
166+
{
167+
RCLCPP_ERROR_THROTTLE(
168+
get_node()->get_logger(), *get_node()->get_clock(), 1000,
169+
"Invalid pose [%f, %f, %f], [%f, %f, %f, %f]", pose.position.x, pose.position.y,
170+
pose.position.z, pose.orientation.x, pose.orientation.y, pose.orientation.z,
171+
pose.orientation.w);
172+
}
173+
else if (realtime_tf_publisher_ && realtime_tf_publisher_->trylock())
152174
{
153175
bool do_publish = false;
154176
// rlcpp::Time comparisons throw if clock types are not the same

pose_broadcaster/test/test_pose_broadcaster.cpp

Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
// limitations under the License.
1414
#include "test_pose_broadcaster.hpp"
1515

16+
#include <cmath>
17+
#include <limits>
1618
#include <utility>
1719
#include <vector>
1820

@@ -186,6 +188,60 @@ TEST_F(PoseBroadcasterTest, PublishSuccess)
186188
EXPECT_EQ(tf_msg.transforms[0].transform.rotation.w, pose_values_[6]);
187189
}
188190

191+
TEST_F(PoseBroadcasterTest, invalid_pose_no_tf_published)
192+
{
193+
SetUpPoseBroadcaster();
194+
195+
// Set 'pose_name' and 'frame_id' parameters
196+
pose_broadcaster_->get_node()->set_parameter({"pose_name", pose_name_});
197+
pose_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});
198+
199+
// Set 'tf.enable' and 'tf.child_frame_id' parameters
200+
pose_broadcaster_->get_node()->set_parameter({"tf.enable", true});
201+
pose_broadcaster_->get_node()->set_parameter({"tf.child_frame_id", tf_child_frame_id_});
202+
203+
// Configure and activate controller
204+
ASSERT_EQ(
205+
pose_broadcaster_->on_configure(rclcpp_lifecycle::State{}),
206+
controller_interface::CallbackReturn::SUCCESS);
207+
ASSERT_EQ(
208+
pose_broadcaster_->on_activate(rclcpp_lifecycle::State{}),
209+
controller_interface::CallbackReturn::SUCCESS);
210+
211+
ASSERT_TRUE(pose_position_x_.set_value(std::numeric_limits<double>::quiet_NaN()));
212+
213+
// Subscribe to pose topic
214+
geometry_msgs::msg::PoseStamped pose_msg;
215+
subscribe_and_get_message("/test_pose_broadcaster/pose", pose_msg);
216+
217+
// Verify content of pose message
218+
EXPECT_EQ(pose_msg.header.frame_id, frame_id_);
219+
EXPECT_TRUE(std::isnan(pose_msg.pose.position.x)); // We set that to NaN above
220+
EXPECT_EQ(pose_msg.pose.position.y, pose_values_[1]);
221+
EXPECT_EQ(pose_msg.pose.position.z, pose_values_[2]);
222+
EXPECT_EQ(pose_msg.pose.orientation.x, pose_values_[3]);
223+
EXPECT_EQ(pose_msg.pose.orientation.y, pose_values_[4]);
224+
EXPECT_EQ(pose_msg.pose.orientation.z, pose_values_[5]);
225+
EXPECT_EQ(pose_msg.pose.orientation.w, pose_values_[6]);
226+
227+
// Subscribe to tf topic
228+
tf2_msgs::msg::TFMessage tf_msg;
229+
EXPECT_THROW(subscribe_and_get_message("/tf", tf_msg), std::runtime_error);
230+
// Verify that no tf message was sent
231+
ASSERT_EQ(tf_msg.transforms.size(), 0lu);
232+
233+
// Set valid position but invalid quaternion
234+
ASSERT_TRUE(pose_position_x_.set_value(0.0));
235+
ASSERT_TRUE(pose_orientation_x_.set_value(0.0));
236+
ASSERT_TRUE(pose_orientation_y_.set_value(0.0));
237+
ASSERT_TRUE(pose_orientation_z_.set_value(0.0));
238+
ASSERT_TRUE(pose_orientation_w_.set_value(0.0));
239+
240+
EXPECT_THROW(subscribe_and_get_message("/tf", tf_msg), std::runtime_error);
241+
// Verify that no tf message was sent
242+
ASSERT_EQ(tf_msg.transforms.size(), 0lu);
243+
}
244+
189245
int main(int argc, char * argv[])
190246
{
191247
::testing::InitGoogleMock(&argc, argv);

pose_broadcaster/test/test_pose_broadcaster.hpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,8 @@ class PoseBroadcasterTest : public ::testing::Test
3939
const std::string frame_id_ = "pose_base_frame";
4040
const std::string tf_child_frame_id_ = "pose_frame";
4141

42-
std::array<double, 7> pose_values_ = {{1.1, 2.2, 3.3, 4.4, 5.5, 6.6, 7.7}};
42+
std::array<double, 7> pose_values_ = {
43+
{1.1, 2.2, 3.3, 0.39190382, 0.20056212, 0.53197575, 0.72331744}};
4344

4445
hardware_interface::StateInterface pose_position_x_{pose_name_, "position.x", &pose_values_[0]};
4546
hardware_interface::StateInterface pose_position_y_{pose_name_, "position.x", &pose_values_[1]};
@@ -77,7 +78,10 @@ void PoseBroadcasterTest::subscribe_and_get_message(const std::string & topic, T
7778
constexpr size_t max_sub_check_loop_count = 5;
7879
for (size_t i = 0; !received_msg; ++i)
7980
{
80-
ASSERT_LT(i, max_sub_check_loop_count);
81+
if (i >= max_sub_check_loop_count)
82+
{
83+
throw std::runtime_error("Failed to receive message on topic: " + topic);
84+
}
8185

8286
pose_broadcaster_->update(rclcpp::Time{0}, rclcpp::Duration::from_seconds(0.01));
8387

0 commit comments

Comments
 (0)