From 4a085a6b8927a4c2a464b8a76c1cea6c88400502 Mon Sep 17 00:00:00 2001 From: Mike Wake Date: Tue, 4 Feb 2025 19:18:21 +1100 Subject: [PATCH] fix PostStampedArray usage in nav_through_poses_tester_error_msg (#4341) Signed-off-by: Mike Wake --- .../src/system/nav_through_poses_tester_error_msg_node.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/nav2_system_tests/src/system/nav_through_poses_tester_error_msg_node.py b/nav2_system_tests/src/system/nav_through_poses_tester_error_msg_node.py index b2b423392e1..08fddd72141 100755 --- a/nav2_system_tests/src/system/nav_through_poses_tester_error_msg_node.py +++ b/nav2_system_tests/src/system/nav_through_poses_tester_error_msg_node.py @@ -21,7 +21,7 @@ from typing import Optional from action_msgs.msg import GoalStatus -from geometry_msgs.msg import Pose +from geometry_msgs.msg import Pose, PoseStampedArray from geometry_msgs.msg import PoseStamped from geometry_msgs.msg import PoseWithCovarianceStamped from lifecycle_msgs.srv import GetState @@ -137,7 +137,9 @@ def runNavigateAction(self, self.goal_pose = goal_pose if goal_pose is not None else self.goal_pose goal_msg = NavigateThroughPoses.Goal() - goal_msg.poses = [ + goal_msg.poses.header.frame_id = 'map' + goal_msg.poses.header.stamp = self.get_clock().now().to_msg() + goal_msg.poses.poses = [ self.getStampedPoseMsg(self.goal_pose), self.getStampedPoseMsg(self.goal_pose), ]