16 from geometry_msgs.msg
import PoseStamped
19 from rclpy.duration
import Duration
22 Basic navigation demo to go to poses.
29 navigator = BasicNavigator()
32 initial_pose = PoseStamped()
33 initial_pose.header.frame_id =
'map'
34 initial_pose.header.stamp = navigator.get_clock().now().to_msg()
35 initial_pose.pose.position.x = 0.0
36 initial_pose.pose.position.y = 0.0
37 initial_pose.pose.orientation.z = 0.0
38 initial_pose.pose.orientation.w = 1.0
39 navigator.setInitialPose(initial_pose)
47 navigator.waitUntilNav2Active()
59 goal_pose1 = PoseStamped()
60 goal_pose1.header.frame_id =
'map'
61 goal_pose1.header.stamp = navigator.get_clock().now().to_msg()
62 goal_pose1.pose.position.x = 10.15
63 goal_pose1.pose.position.y = -0.77
64 goal_pose1.pose.orientation.w = 1.0
65 goal_pose1.pose.orientation.z = 0.0
66 goal_poses.append(goal_pose1)
69 goal_pose2 = PoseStamped()
70 goal_pose2.header.frame_id =
'map'
71 goal_pose2.header.stamp = navigator.get_clock().now().to_msg()
72 goal_pose2.pose.position.x = 17.86
73 goal_pose2.pose.position.y = -0.77
74 goal_pose2.pose.orientation.w = 1.0
75 goal_pose2.pose.orientation.z = 0.0
76 goal_poses.append(goal_pose2)
77 goal_pose3 = PoseStamped()
78 goal_pose3.header.frame_id =
'map'
79 goal_pose3.header.stamp = navigator.get_clock().now().to_msg()
80 goal_pose3.pose.position.x = 21.58
81 goal_pose3.pose.position.y = -3.5
82 goal_pose3.pose.orientation.w = 1.0
83 goal_pose3.pose.orientation.z = 0.0
84 goal_poses.append(goal_pose3)
89 nav_start = navigator.get_clock().now()
90 navigator.followWaypoints(goal_poses)
93 while not navigator.isTaskComplete():
102 feedback = navigator.getFeedback()
103 if feedback
and i % 5 == 0:
105 'Executing current waypoint: '
106 + str(feedback.current_waypoint + 1)
108 + str(len(goal_poses))
110 now = navigator.get_clock().now()
113 if now - nav_start > Duration(seconds=600.0):
114 navigator.cancelTask()
117 if now - nav_start > Duration(seconds=35.0):
118 goal_pose4 = PoseStamped()
119 goal_pose4.header.frame_id =
'map'
120 goal_pose4.header.stamp = now.to_msg()
121 goal_pose4.pose.position.x = 0.0
122 goal_pose4.pose.position.y = 0.0
123 goal_pose4.pose.orientation.w = 1.0
124 goal_pose4.pose.orientation.z = 0.0
125 goal_poses = [goal_pose4]
127 navigator.followWaypoints(goal_poses)
130 result = navigator.getResult()
131 if result == TaskResult.SUCCEEDED:
132 print(
'Goal succeeded!')
133 elif result == TaskResult.CANCELED:
134 print(
'Goal was canceled!')
135 elif result == TaskResult.FAILED:
136 print(
'Goal failed!')
138 print(
'Goal has an invalid return status!')
140 navigator.lifecycleShutdown()
145 if __name__ ==
'__main__':