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 = 3.45
36 initial_pose.pose.position.y = 2.15
37 initial_pose.pose.orientation.z = 1.0
38 initial_pose.pose.orientation.w = 0.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 = 1.5
63 goal_pose1.pose.position.y = 0.55
64 goal_pose1.pose.orientation.w = 0.707
65 goal_pose1.pose.orientation.z = 0.707
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 = 1.5
73 goal_pose2.pose.position.y = -3.75
74 goal_pose2.pose.orientation.w = 0.707
75 goal_pose2.pose.orientation.z = 0.707
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 = -3.6
81 goal_pose3.pose.position.y = -4.75
82 goal_pose3.pose.orientation.w = 0.707
83 goal_pose3.pose.orientation.z = 0.707
84 goal_poses.append(goal_pose3)
89 navigator.goThroughPoses(goal_poses)
92 while not navigator.isTaskComplete():
101 feedback = navigator.getFeedback()
102 if feedback
and i % 5 == 0:
103 print(
'Estimated time of arrival: ' +
'{0:.0f}'.format(
104 Duration.from_msg(feedback.estimated_time_remaining).nanoseconds / 1e9)
108 if Duration.from_msg(feedback.navigation_time) > Duration(seconds=600.0):
109 navigator.cancelTask()
112 if Duration.from_msg(feedback.navigation_time) > Duration(seconds=35.0):
113 goal_pose4 = PoseStamped()
114 goal_pose4.header.frame_id =
'map'
115 goal_pose4.header.stamp = navigator.get_clock().now().to_msg()
116 goal_pose4.pose.position.x = -5.0
117 goal_pose4.pose.position.y = -4.75
118 goal_pose4.pose.orientation.w = 0.707
119 goal_pose4.pose.orientation.z = 0.707
120 navigator.goThroughPoses([goal_pose4])
123 result = navigator.getResult()
124 if result == TaskResult.SUCCEEDED:
125 print(
'Goal succeeded!')
126 elif result == TaskResult.CANCELED:
127 print(
'Goal was canceled!')
128 elif result == TaskResult.FAILED:
129 print(
'Goal failed!')
131 print(
'Goal has an invalid return status!')
133 navigator.lifecycleShutdown()
138 if __name__ ==
'__main__':