Skip to content

Commit 081e114

Browse files
Vortex-THenricosutera
authored andcommitted
Add DriveOnHeading (ros-navigation#4022)
* Add DriveOnHeading Signed-off-by: thass <3118243+Vortex-TH@users.noreply.github.com> * Fix style errors Signed-off-by: thass <3118243+Vortex-TH@users.noreply.github.com> --------- Signed-off-by: thass <3118243+Vortex-TH@users.noreply.github.com> Signed-off-by: enricosutera <enricosutera@outlook.com>
1 parent c64645a commit 081e114

File tree

1 file changed

+28
-1
lines changed

1 file changed

+28
-1
lines changed

nav2_simple_commander/nav2_simple_commander/robot_navigator.py

Lines changed: 28 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323
from geometry_msgs.msg import PoseStamped
2424
from geometry_msgs.msg import PoseWithCovarianceStamped
2525
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
2727
from nav2_msgs.action import ComputePathThroughPoses, ComputePathToPose
2828
from nav2_msgs.action import (
2929
FollowGPSWaypoints,
@@ -88,6 +88,9 @@ def __init__(self, node_name='basic_navigator', namespace=''):
8888
self.smoother_client = ActionClient(self, SmoothPath, 'smooth_path')
8989
self.spin_client = ActionClient(self, Spin, 'spin')
9090
self.backup_client = ActionClient(self, BackUp, 'backup')
91+
self.drive_on_heading_client = ActionClient(
92+
self, DriveOnHeading, 'drive_on_heading'
93+
)
9194
self.assisted_teleop_client = ActionClient(
9295
self, AssistedTeleop, 'assisted_teleop'
9396
)
@@ -127,6 +130,7 @@ def destroy_node(self):
127130
self.smoother_client.destroy()
128131
self.spin_client.destroy()
129132
self.backup_client.destroy()
133+
self.drive_on_heading_client.destroy()
130134
super().destroy_node()
131135

132136
def setInitialPose(self, initial_pose):
@@ -288,6 +292,29 @@ def backup(self, backup_dist=0.15, backup_speed=0.025, time_allowance=10):
288292
self.result_future = self.goal_handle.get_result_async()
289293
return True
290294

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+
291318
def assistedTeleop(self, time_allowance=30):
292319
self.debug("Wainting for 'assisted_teleop' action server")
293320
while not self.assisted_teleop_client.wait_for_server(timeout_sec=1.0):

0 commit comments

Comments
 (0)