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 = 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()
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 = -2.0
62 goal_pose.pose.position.y = -0.5
63 goal_pose.pose.orientation.w = 1.0
68 navigator.goToPose(goal_pose)
71 while not navigator.isTaskComplete():
80 feedback = navigator.getFeedback()
81 if feedback
and i % 5 == 0:
82 print(
'Estimated time of arrival: ' +
'{0:.0f}'.format(
83 Duration.from_msg(feedback.estimated_time_remaining).nanoseconds / 1e9)
87 if Duration.from_msg(feedback.navigation_time) > Duration(seconds=600.0):
88 navigator.cancelTask()
91 if Duration.from_msg(feedback.navigation_time) > Duration(seconds=18.0):
92 goal_pose.pose.position.x = -3.0
93 navigator.goToPose(goal_pose)
96 result = navigator.getResult()
97 if result == TaskResult.SUCCEEDED:
98 print(
'Goal succeeded!')
99 elif result == TaskResult.CANCELED:
100 print(
'Goal was canceled!')
101 elif result == TaskResult.FAILED:
102 print(
'Goal failed!')
104 print(
'Goal has an invalid return status!')
106 navigator.lifecycleShutdown()
111 if __name__ ==
'__main__':