Skip to content

Commit

Permalink
fix PostStampedArray usage in nav_through_poses_tester_error_msg (ros…
Browse files Browse the repository at this point in the history
…-navigation#4341)

Signed-off-by: Mike Wake <[email protected]>
  • Loading branch information
ewak committed Feb 11, 2025
1 parent 8ad594b commit 4a085a6
Showing 1 changed file with 4 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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),
]
Expand Down

0 comments on commit 4a085a6

Please sign in to comment.