... | ... | @@ -244,7 +244,7 @@ from rclpy.action import ActionClient |
|
|
from rclpy.node import Node
|
|
|
|
|
|
from nav2_msgs.action import NavigateToPose
|
|
|
|
|
|
import threading
|
|
|
|
|
|
class RandomExploration(Node):
|
|
|
|
... | ... | @@ -284,7 +284,8 @@ class RandomExploration(Node): |
|
|
print(feedback_msg.feedback)
|
|
|
self.get_logger().info('Received feedback: {0}'.format(feedback_msg.feedback.navigation_time))
|
|
|
if feedback_msg.feedback.navigation_time.sec > 60:
|
|
|
self._goal_handle.cancel_goal()
|
|
|
self.cancel_thread = threading.Thread(target=self._goal_handle.cancel_goal)
|
|
|
self.cancel_thread.start()
|
|
|
rclpy.shutdown()
|
|
|
|
|
|
|
... | ... | |