|
23 | 23 | from geometry_msgs.msg import PoseStamped |
24 | 24 | from geometry_msgs.msg import PoseWithCovarianceStamped |
25 | 25 | from lifecycle_msgs.srv import GetState |
26 | | -from nav2_msgs.action import AssistedTeleop, BackUp, Spin |
| 26 | +from nav2_msgs.action import AssistedTeleop, BackUp, DriveOnHeading, Spin |
27 | 27 | from nav2_msgs.action import ComputePathThroughPoses, ComputePathToPose |
28 | 28 | from nav2_msgs.action import ( |
29 | 29 | FollowGPSWaypoints, |
@@ -88,6 +88,9 @@ def __init__(self, node_name='basic_navigator', namespace=''): |
88 | 88 | self.smoother_client = ActionClient(self, SmoothPath, 'smooth_path') |
89 | 89 | self.spin_client = ActionClient(self, Spin, 'spin') |
90 | 90 | self.backup_client = ActionClient(self, BackUp, 'backup') |
| 91 | + self.drive_on_heading_client = ActionClient( |
| 92 | + self, DriveOnHeading, 'drive_on_heading' |
| 93 | + ) |
91 | 94 | self.assisted_teleop_client = ActionClient( |
92 | 95 | self, AssistedTeleop, 'assisted_teleop' |
93 | 96 | ) |
@@ -127,6 +130,7 @@ def destroy_node(self): |
127 | 130 | self.smoother_client.destroy() |
128 | 131 | self.spin_client.destroy() |
129 | 132 | self.backup_client.destroy() |
| 133 | + self.drive_on_heading_client.destroy() |
130 | 134 | super().destroy_node() |
131 | 135 |
|
132 | 136 | def setInitialPose(self, initial_pose): |
@@ -288,6 +292,29 @@ def backup(self, backup_dist=0.15, backup_speed=0.025, time_allowance=10): |
288 | 292 | self.result_future = self.goal_handle.get_result_async() |
289 | 293 | return True |
290 | 294 |
|
| 295 | + def driveOnHeading(self, dist=0.15, speed=0.025, time_allowance=10): |
| 296 | + self.debug("Waiting for 'DriveOnHeading' action server") |
| 297 | + while not self.backup_client.wait_for_server(timeout_sec=1.0): |
| 298 | + self.info("'DriveOnHeading' action server not available, waiting...") |
| 299 | + goal_msg = DriveOnHeading.Goal() |
| 300 | + goal_msg.target = Point(x=float(dist)) |
| 301 | + goal_msg.speed = speed |
| 302 | + goal_msg.time_allowance = Duration(sec=time_allowance) |
| 303 | + |
| 304 | + self.info(f'Drive {goal_msg.target.x} m on heading at {goal_msg.speed} m/s....') |
| 305 | + send_goal_future = self.drive_on_heading_client.send_goal_async( |
| 306 | + goal_msg, self._feedbackCallback |
| 307 | + ) |
| 308 | + rclpy.spin_until_future_complete(self, send_goal_future) |
| 309 | + self.goal_handle = send_goal_future.result() |
| 310 | + |
| 311 | + if not self.goal_handle.accepted: |
| 312 | + self.error('Drive On Heading request was rejected!') |
| 313 | + return False |
| 314 | + |
| 315 | + self.result_future = self.goal_handle.get_result_async() |
| 316 | + return True |
| 317 | + |
291 | 318 | def assistedTeleop(self, time_allowance=30): |
292 | 319 | self.debug("Wainting for 'assisted_teleop' action server") |
293 | 320 | while not self.assisted_teleop_client.wait_for_server(timeout_sec=1.0): |
|
0 commit comments