|
13 | 13 | // limitations under the License.
|
14 | 14 | #include "test_pose_broadcaster.hpp"
|
15 | 15 |
|
| 16 | +#include <cmath> |
| 17 | +#include <limits> |
16 | 18 | #include <utility>
|
17 | 19 | #include <vector>
|
18 | 20 |
|
@@ -186,6 +188,60 @@ TEST_F(PoseBroadcasterTest, PublishSuccess)
|
186 | 188 | EXPECT_EQ(tf_msg.transforms[0].transform.rotation.w, pose_values_[6]);
|
187 | 189 | }
|
188 | 190 |
|
| 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 | + |
189 | 245 | int main(int argc, char * argv[])
|
190 | 246 | {
|
191 | 247 | ::testing::InitGoogleMock(&argc, argv);
|
|
0 commit comments