diff --git a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp index d370662604..d49e17ab77 100644 --- a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp @@ -96,6 +96,7 @@ class ServerGoalHandle : public ServerGoalHandleBase void publish_feedback(std::shared_ptr feedback_msg) { + feedback_msg->uuid = uuid_; _publish_feedback(std::static_pointer_cast(feedback_msg)); } diff --git a/rclcpp_action/test/test_server.cpp b/rclcpp_action/test/test_server.cpp index 15b6e3d97c..fbcfad14c6 100644 --- a/rclcpp_action/test/test_server.cpp +++ b/rclcpp_action/test/test_server.cpp @@ -543,6 +543,7 @@ TEST_F(TestServer, publish_feedback) ASSERT_EQ(1u, received_msgs.size()); auto & msg = received_msgs.back(); ASSERT_EQ(sent_message->sequence, msg->sequence); + ASSERT_EQ(uuid, msg->uuid); } TEST_F(TestServer, get_result)