16 from geometry_msgs.msg
import PoseStamped
19 from rclpy.duration
import Duration
22 Basic navigation demo to go to pose.
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()
58 goal_pose = PoseStamped()
59 goal_pose.header.frame_id =
'map'
60 goal_pose.header.stamp = navigator.get_clock().now().to_msg()
61 goal_pose.pose.position.x = 17.86
62 goal_pose.pose.position.y = -0.77
63 goal_pose.pose.orientation.w = 1.0
64 goal_pose.pose.orientation.z = 0.0
69 navigator.goToPose(goal_pose)
72 while not navigator.isTaskComplete():
81 feedback = navigator.getFeedback()
82 if feedback
and i % 5 == 0:
84 'Estimated time of arrival: '
86 Duration.from_msg(feedback.estimated_time_remaining).nanoseconds
93 if Duration.from_msg(feedback.navigation_time) > Duration(seconds=600.0):
94 navigator.cancelTask()
97 if Duration.from_msg(feedback.navigation_time) > Duration(seconds=18.0):
98 goal_pose.pose.position.x = 0.0
99 goal_pose.pose.position.y = 0.0
100 navigator.goToPose(goal_pose)
103 result = navigator.getResult()
104 if result == TaskResult.SUCCEEDED:
105 print(
'Goal succeeded!')
106 elif result == TaskResult.CANCELED:
107 print(
'Goal was canceled!')
108 elif result == TaskResult.FAILED:
109 print(
'Goal failed!')
111 print(
'Goal has an invalid return status!')
113 navigator.lifecycleShutdown()
118 if __name__ ==
'__main__':