20 from action_msgs.msg
import GoalStatus
21 from builtin_interfaces.msg
import Duration
22 from geometry_msgs.msg
import Point
23 from geometry_msgs.msg
import PoseStamped
24 from geometry_msgs.msg
import PoseWithCovarianceStamped
25 from lifecycle_msgs.srv
import GetState
26 from nav2_msgs.action
import AssistedTeleop, BackUp, DriveOnHeading, Spin
27 from nav2_msgs.action
import ComputePathThroughPoses, ComputePathToPose
28 from nav2_msgs.action
import (
37 from nav2_msgs.action
import SmoothPath
38 from nav2_msgs.srv
import ClearCostmapAroundPose, ClearCostmapAroundRobot, \
39 ClearCostmapExceptRegion, ClearEntireCostmap
40 from nav2_msgs.srv
import GetCostmap, LoadMap, ManageLifecycleNodes
42 from rclpy.action
import ActionClient
43 from rclpy.duration
import Duration
as rclpyDuration
44 from rclpy.node
import Node
45 from rclpy.qos
import QoSDurabilityPolicy, QoSHistoryPolicy
46 from rclpy.qos
import QoSProfile, QoSReliabilityPolicy
58 def __init__(self, node_name='basic_navigator', namespace=''):
59 super().__init__(node_name=node_name, namespace=namespace)
67 amcl_pose_qos = QoSProfile(
68 durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
69 reliability=QoSReliabilityPolicy.RELIABLE,
70 history=QoSHistoryPolicy.KEEP_LAST,
76 self, NavigateThroughPoses,
'navigate_through_poses'
78 self.
nav_to_pose_clientnav_to_pose_client = ActionClient(self, NavigateToPose,
'navigate_to_pose')
80 self, FollowWaypoints,
'follow_waypoints'
83 self, FollowGPSWaypoints,
'follow_gps_waypoints'
85 self.
follow_path_clientfollow_path_client = ActionClient(self, FollowPath,
'follow_path')
87 self, ComputePathToPose,
'compute_path_to_pose'
90 self, ComputePathThroughPoses,
'compute_path_through_poses'
92 self.
smoother_clientsmoother_client = ActionClient(self, SmoothPath,
'smooth_path')
93 self.
spin_clientspin_client = ActionClient(self, Spin,
'spin')
94 self.
backup_clientbackup_client = ActionClient(self, BackUp,
'backup')
96 self, DriveOnHeading,
'drive_on_heading'
99 self, AssistedTeleop,
'assisted_teleop'
101 self.
docking_clientdocking_client = ActionClient(self, DockRobot,
'dock_robot')
102 self.
undocking_clientundocking_client = ActionClient(self, UndockRobot,
'undock_robot')
104 PoseWithCovarianceStamped,
110 PoseWithCovarianceStamped,
'initialpose', 10
112 self.
change_maps_srvchange_maps_srv = self.create_client(LoadMap,
'map_server/load_map')
114 ClearEntireCostmap,
'global_costmap/clear_entirely_global_costmap'
117 ClearEntireCostmap,
'local_costmap/clear_entirely_local_costmap'
120 ClearCostmapExceptRegion,
'local_costmap/clear_costmap_except_region'
123 ClearCostmapAroundRobot,
'local_costmap/clear_costmap_around_robot'
126 ClearCostmapAroundPose,
'local_costmap/clear_costmap_around_pose'
129 GetCostmap,
'global_costmap/get_costmap'
132 GetCostmap,
'local_costmap/get_costmap'
135 def destroyNode(self):
138 def destroy_node(self):
153 super().destroy_node()
156 """Set the initial pose to the localization system."""
162 """Send a `NavThroughPoses` action request."""
163 self.
debugdebug(
"Waiting for 'NavigateThroughPoses' action server")
165 self.
infoinfo(
"'NavigateThroughPoses' action server not available, waiting...")
167 goal_msg = NavigateThroughPoses.Goal()
168 goal_msg.poses = poses
169 goal_msg.behavior_tree = behavior_tree
171 self.
infoinfo(f
'Navigating with {len(goal_msg.poses)} goals....')
175 rclpy.spin_until_future_complete(self, send_goal_future)
176 self.
goal_handlegoal_handle = send_goal_future.result()
179 self.
errorerror(f
'Goal with {len(poses)} poses was rejected!')
186 """Send a `NavToPose` action request."""
187 self.
debugdebug(
"Waiting for 'NavigateToPose' action server")
189 self.
infoinfo(
"'NavigateToPose' action server not available, waiting...")
191 goal_msg = NavigateToPose.Goal()
193 goal_msg.behavior_tree = behavior_tree
196 'Navigating to goal: '
197 + str(pose.pose.position.x)
199 + str(pose.pose.position.y)
205 rclpy.spin_until_future_complete(self, send_goal_future)
206 self.
goal_handlegoal_handle = send_goal_future.result()
211 + str(pose.pose.position.x)
213 + str(pose.pose.position.y)
222 """Send a `FollowWaypoints` action request."""
223 self.
debugdebug(
"Waiting for 'FollowWaypoints' action server")
225 self.
infoinfo(
"'FollowWaypoints' action server not available, waiting...")
227 goal_msg = FollowWaypoints.Goal()
228 goal_msg.poses = poses
230 self.
infoinfo(f
'Following {len(goal_msg.poses)} goals....')
234 rclpy.spin_until_future_complete(self, send_goal_future)
235 self.
goal_handlegoal_handle = send_goal_future.result()
238 self.
errorerror(f
'Following {len(poses)} waypoints request was rejected!')
245 """Send a `FollowGPSWaypoints` action request."""
246 self.
debugdebug(
"Waiting for 'FollowWaypoints' action server")
248 self.
infoinfo(
"'FollowWaypoints' action server not available, waiting...")
250 goal_msg = FollowGPSWaypoints.Goal()
251 goal_msg.gps_poses = gps_poses
253 self.
infoinfo(f
'Following {len(goal_msg.gps_poses)} gps goals....')
257 rclpy.spin_until_future_complete(self, send_goal_future)
258 self.
goal_handlegoal_handle = send_goal_future.result()
262 f
'Following {len(gps_poses)} gps waypoints request was rejected!'
269 def spin(self, spin_dist=1.57, time_allowance=10):
270 self.
debugdebug(
"Waiting for 'Spin' action server")
271 while not self.
spin_clientspin_client.wait_for_server(timeout_sec=1.0):
272 self.
infoinfo(
"'Spin' action server not available, waiting...")
273 goal_msg = Spin.Goal()
274 goal_msg.target_yaw = spin_dist
275 goal_msg.time_allowance = Duration(sec=time_allowance)
277 self.
infoinfo(f
'Spinning to angle {goal_msg.target_yaw}....')
278 send_goal_future = self.
spin_clientspin_client.send_goal_async(
281 rclpy.spin_until_future_complete(self, send_goal_future)
282 self.
goal_handlegoal_handle = send_goal_future.result()
285 self.
errorerror(
'Spin request was rejected!')
291 def backup(self, backup_dist=0.15, backup_speed=0.025, time_allowance=10):
292 self.
debugdebug(
"Waiting for 'Backup' action server")
293 while not self.
backup_clientbackup_client.wait_for_server(timeout_sec=1.0):
294 self.
infoinfo(
"'Backup' action server not available, waiting...")
295 goal_msg = BackUp.Goal()
296 goal_msg.target = Point(x=float(backup_dist))
297 goal_msg.speed = backup_speed
298 goal_msg.time_allowance = Duration(sec=time_allowance)
300 self.
infoinfo(f
'Backing up {goal_msg.target.x} m at {goal_msg.speed} m/s....')
301 send_goal_future = self.
backup_clientbackup_client.send_goal_async(
304 rclpy.spin_until_future_complete(self, send_goal_future)
305 self.
goal_handlegoal_handle = send_goal_future.result()
308 self.
errorerror(
'Backup request was rejected!')
314 def driveOnHeading(self, dist=0.15, speed=0.025, time_allowance=10):
315 self.
debugdebug(
"Waiting for 'DriveOnHeading' action server")
316 while not self.
backup_clientbackup_client.wait_for_server(timeout_sec=1.0):
317 self.
infoinfo(
"'DriveOnHeading' action server not available, waiting...")
318 goal_msg = DriveOnHeading.Goal()
319 goal_msg.target = Point(x=float(dist))
320 goal_msg.speed = speed
321 goal_msg.time_allowance = Duration(sec=time_allowance)
323 self.
infoinfo(f
'Drive {goal_msg.target.x} m on heading at {goal_msg.speed} m/s....')
327 rclpy.spin_until_future_complete(self, send_goal_future)
328 self.
goal_handlegoal_handle = send_goal_future.result()
331 self.
errorerror(
'Drive On Heading request was rejected!')
337 def assistedTeleop(self, time_allowance=30):
338 self.
debugdebug(
"Wainting for 'assisted_teleop' action server")
340 self.
infoinfo(
"'assisted_teleop' action server not available, waiting...")
341 goal_msg = AssistedTeleop.Goal()
342 goal_msg.time_allowance = Duration(sec=time_allowance)
344 self.
infoinfo(
"Running 'assisted_teleop'....")
348 rclpy.spin_until_future_complete(self, send_goal_future)
349 self.
goal_handlegoal_handle = send_goal_future.result()
352 self.
errorerror(
'Assisted Teleop request was rejected!')
358 def followPath(self, path, controller_id='', goal_checker_id=''):
359 """Send a `FollowPath` action request."""
360 self.
debugdebug(
"Waiting for 'FollowPath' action server")
362 self.
infoinfo(
"'FollowPath' action server not available, waiting...")
364 goal_msg = FollowPath.Goal()
366 goal_msg.controller_id = controller_id
367 goal_msg.goal_checker_id = goal_checker_id
369 self.
infoinfo(
'Executing path...')
373 rclpy.spin_until_future_complete(self, send_goal_future)
374 self.
goal_handlegoal_handle = send_goal_future.result()
377 self.
errorerror(
'Follow path was rejected!')
384 """Send a `DockRobot` action request."""
385 self.
infoinfo(
"Waiting for 'DockRobot' action server")
386 while not self.
docking_clientdocking_client.wait_for_server(timeout_sec=1.0):
387 self.
infoinfo(
'"DockRobot" action server not available, waiting...')
389 goal_msg = DockRobot.Goal()
390 goal_msg.use_dock_id =
False
391 goal_msg.dock_pose = dock_pose
392 goal_msg.dock_type = dock_type
393 goal_msg.navigate_to_staging_pose = nav_to_dock
395 self.
infoinfo(
'Docking at pose: ' + str(dock_pose) +
'...')
396 send_goal_future = self.
docking_clientdocking_client.send_goal_async(goal_msg,
398 rclpy.spin_until_future_complete(self, send_goal_future)
399 self.
goal_handlegoal_handle = send_goal_future.result()
402 self.
infoinfo(
'Docking request was rejected!')
409 """Send a `DockRobot` action request."""
410 self.
infoinfo(
"Waiting for 'DockRobot' action server")
411 while not self.
docking_clientdocking_client.wait_for_server(timeout_sec=1.0):
412 self.
infoinfo(
'"DockRobot" action server not available, waiting...')
414 goal_msg = DockRobot.Goal()
415 goal_msg.use_dock_id =
True
416 goal_msg.dock_id = dock_id
417 goal_msg.navigate_to_staging_pose = nav_to_dock
419 self.
infoinfo(
'Docking at dock ID: ' + str(dock_id) +
'...')
420 send_goal_future = self.
docking_clientdocking_client.send_goal_async(goal_msg,
422 rclpy.spin_until_future_complete(self, send_goal_future)
423 self.
goal_handlegoal_handle = send_goal_future.result()
426 self.
infoinfo(
'Docking request was rejected!')
433 """Send a `UndockRobot` action request."""
434 self.
infoinfo(
"Waiting for 'UndockRobot' action server")
435 while not self.
undocking_clientundocking_client.wait_for_server(timeout_sec=1.0):
436 self.
infoinfo(
'"UndockRobot" action server not available, waiting...')
438 goal_msg = UndockRobot.Goal()
439 goal_msg.dock_type = dock_type
441 self.
infoinfo(
'Undocking from dock of type: ' + str(dock_type) +
'...')
442 send_goal_future = self.
undocking_clientundocking_client.send_goal_async(goal_msg,
444 rclpy.spin_until_future_complete(self, send_goal_future)
445 self.
goal_handlegoal_handle = send_goal_future.result()
448 self.
infoinfo(
'Undocking request was rejected!')
455 """Cancel pending task request of any type."""
456 self.
infoinfo(
'Canceling current task.')
458 future = self.
goal_handlegoal_handle.cancel_goal_async()
459 rclpy.spin_until_future_complete(self, future)
463 """Check if the task request of any type is complete yet."""
467 rclpy.spin_until_future_complete(self, self.
result_futureresult_future, timeout_sec=0.10)
470 if self.
statusstatus != GoalStatus.STATUS_SUCCEEDED:
471 self.
debugdebug(f
'Task with failed with status code: {self.status}')
477 self.
debugdebug(
'Task succeeded!')
481 """Get the pending action feedback message."""
485 """Get the pending action result message."""
486 if self.
statusstatus == GoalStatus.STATUS_SUCCEEDED:
487 return TaskResult.SUCCEEDED
488 elif self.
statusstatus == GoalStatus.STATUS_ABORTED:
489 return TaskResult.FAILED
490 elif self.
statusstatus == GoalStatus.STATUS_CANCELED:
491 return TaskResult.CANCELED
493 return TaskResult.UNKNOWN
496 """Block until the full navigation system is up and running."""
497 if localizer !=
'robot_localization':
499 if localizer ==
'amcl':
502 self.
infoinfo(
'Nav2 is ready for use!')
505 def _getPathImpl(self, start, goal, planner_id='', use_start=False):
507 Send a `ComputePathToPose` action request.
509 Internal implementation to get the full result, not just the path.
511 self.
debugdebug(
"Waiting for 'ComputePathToPose' action server")
513 self.
infoinfo(
"'ComputePathToPose' action server not available, waiting...")
515 goal_msg = ComputePathToPose.Goal()
516 goal_msg.start = start
518 goal_msg.planner_id = planner_id
519 goal_msg.use_start = use_start
521 self.
infoinfo(
'Getting path...')
523 rclpy.spin_until_future_complete(self, send_goal_future)
524 self.
goal_handlegoal_handle = send_goal_future.result()
527 self.
errorerror(
'Get path was rejected!')
531 rclpy.spin_until_future_complete(self, self.
result_futureresult_future)
536 def getPath(self, start, goal, planner_id='', use_start=False):
537 """Send a `ComputePathToPose` action request."""
538 rtn = self.
_getPathImpl_getPathImpl(start, goal, planner_id, use_start)
540 if self.
statusstatus != GoalStatus.STATUS_SUCCEEDED:
541 self.
warnwarn(f
'Getting path failed with status code: {self.status}')
549 def _getPathThroughPosesImpl(self, start, goals, planner_id='', use_start=False):
551 Send a `ComputePathThroughPoses` action request.
553 Internal implementation to get the full result, not just the path.
555 self.
debugdebug(
"Waiting for 'ComputePathThroughPoses' action server")
560 "'ComputePathThroughPoses' action server not available, waiting..."
563 goal_msg = ComputePathThroughPoses.Goal()
564 goal_msg.start = start
565 goal_msg.goals = goals
566 goal_msg.planner_id = planner_id
567 goal_msg.use_start = use_start
569 self.
infoinfo(
'Getting path...')
573 rclpy.spin_until_future_complete(self, send_goal_future)
574 self.
goal_handlegoal_handle = send_goal_future.result()
577 self.
errorerror(
'Get path was rejected!')
581 rclpy.spin_until_future_complete(self, self.
result_futureresult_future)
587 """Send a `ComputePathThroughPoses` action request."""
590 if self.
statusstatus != GoalStatus.STATUS_SUCCEEDED:
591 self.
warnwarn(f
'Getting path failed with status code: {self.status}')
600 self, path, smoother_id='', max_duration=2.0, check_for_collision=False
603 Send a `SmoothPath` action request.
605 Internal implementation to get the full result, not just the path.
607 self.
debugdebug(
"Waiting for 'SmoothPath' action server")
608 while not self.
smoother_clientsmoother_client.wait_for_server(timeout_sec=1.0):
609 self.
infoinfo(
"'SmoothPath' action server not available, waiting...")
611 goal_msg = SmoothPath.Goal()
613 goal_msg.max_smoothing_duration = rclpyDuration(seconds=max_duration).to_msg()
614 goal_msg.smoother_id = smoother_id
615 goal_msg.check_for_collisions = check_for_collision
617 self.
infoinfo(
'Smoothing path...')
618 send_goal_future = self.
smoother_clientsmoother_client.send_goal_async(goal_msg)
619 rclpy.spin_until_future_complete(self, send_goal_future)
620 self.
goal_handlegoal_handle = send_goal_future.result()
623 self.
errorerror(
'Smooth path was rejected!')
627 rclpy.spin_until_future_complete(self, self.
result_futureresult_future)
633 self, path, smoother_id='', max_duration=2.0, check_for_collision=False
635 """Send a `SmoothPath` action request."""
636 rtn = self.
_smoothPathImpl_smoothPathImpl(path, smoother_id, max_duration, check_for_collision)
638 if self.
statusstatus != GoalStatus.STATUS_SUCCEEDED:
639 self.
warnwarn(f
'Getting path failed with status code: {self.status}')
648 """Change the current static map in the map server."""
649 while not self.
change_maps_srvchange_maps_srv.wait_for_service(timeout_sec=1.0):
650 self.
infoinfo(
'change map service not available, waiting...')
651 req = LoadMap.Request()
652 req.map_url = map_filepath
654 rclpy.spin_until_future_complete(self, future)
655 status = future.result().result
656 if status != LoadMap.Response().RESULT_SUCCESS:
657 self.
errorerror(
'Change map request failed!')
659 self.
infoinfo(
'Change map request was successful!')
663 """Clear all costmaps."""
669 """Clear local costmap."""
671 self.
infoinfo(
'Clear local costmaps service not available, waiting...')
672 req = ClearEntireCostmap.Request()
674 rclpy.spin_until_future_complete(self, future)
678 """Clear global costmap."""
680 self.
infoinfo(
'Clear global costmaps service not available, waiting...')
681 req = ClearEntireCostmap.Request()
683 rclpy.spin_until_future_complete(self, future)
687 """Clear the costmap except for a specified region."""
689 self.
infoinfo(
'ClearCostmapExceptRegion service not available, waiting...')
690 req = ClearCostmapExceptRegion.Request()
691 req.reset_distance = reset_distance
693 rclpy.spin_until_future_complete(self, future)
697 """Clear the costmap around the robot."""
699 self.
infoinfo(
'ClearCostmapAroundRobot service not available, waiting...')
700 req = ClearCostmapAroundRobot.Request()
701 req.reset_distance = reset_distance
703 rclpy.spin_until_future_complete(self, future)
707 """Clear the costmap around a specified pose."""
709 self.
infoinfo(
'ClearCostmapAroundPose service not available, waiting...')
710 req = ClearCostmapAroundPose.Request()
712 req.reset_distance = reset_distance
714 rclpy.spin_until_future_complete(self, future)
718 """Get the global costmap."""
720 self.
infoinfo(
'Get global costmaps service not available, waiting...')
721 req = GetCostmap.Request()
723 rclpy.spin_until_future_complete(self, future)
724 return future.result().map
727 """Get the local costmap."""
729 self.
infoinfo(
'Get local costmaps service not available, waiting...')
730 req = GetCostmap.Request()
732 rclpy.spin_until_future_complete(self, future)
733 return future.result().map
736 """Startup nav2 lifecycle system."""
737 self.
infoinfo(
'Starting up lifecycle nodes based on lifecycle_manager.')
738 for srv_name, srv_type
in self.get_service_names_and_types():
739 if srv_type[0] ==
'nav2_msgs/srv/ManageLifecycleNodes':
740 self.
infoinfo(f
'Starting up {srv_name}')
741 mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
742 while not mgr_client.wait_for_service(timeout_sec=1.0):
743 self.
infoinfo(f
'{srv_name} service not available, waiting...')
744 req = ManageLifecycleNodes.Request()
745 req.command = ManageLifecycleNodes.Request().STARTUP
746 future = mgr_client.call_async(req)
751 rclpy.spin_until_future_complete(self, future, timeout_sec=0.10)
756 self.
infoinfo(
'Nav2 is ready for use!')
760 """Shutdown nav2 lifecycle system."""
761 self.
infoinfo(
'Shutting down lifecycle nodes based on lifecycle_manager.')
762 for srv_name, srv_type
in self.get_service_names_and_types():
763 if srv_type[0] ==
'nav2_msgs/srv/ManageLifecycleNodes':
764 self.
infoinfo(f
'Shutting down {srv_name}')
765 mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
766 while not mgr_client.wait_for_service(timeout_sec=1.0):
767 self.
infoinfo(f
'{srv_name} service not available, waiting...')
768 req = ManageLifecycleNodes.Request()
769 req.command = ManageLifecycleNodes.Request().SHUTDOWN
770 future = mgr_client.call_async(req)
771 rclpy.spin_until_future_complete(self, future)
775 def _waitForNodeToActivate(self, node_name):
777 self.
debugdebug(f
'Waiting for {node_name} to become active..')
778 node_service = f
'{node_name}/get_state'
779 state_client = self.create_client(GetState, node_service)
780 while not state_client.wait_for_service(timeout_sec=1.0):
781 self.
infoinfo(f
'{node_service} service not available, waiting...')
783 req = GetState.Request()
785 while state !=
'active':
786 self.
debugdebug(f
'Getting {node_name} state...')
787 future = state_client.call_async(req)
788 rclpy.spin_until_future_complete(self, future)
789 if future.result()
is not None:
790 state = future.result().current_state.label
791 self.
debugdebug(f
'Result of get_state: {state}')
795 def _waitForInitialPose(self):
797 self.
infoinfo(
'Setting initial pose')
799 self.
infoinfo(
'Waiting for amcl_pose to be received')
800 rclpy.spin_once(self, timeout_sec=1.0)
803 def _amclPoseCallback(self, msg):
804 self.
debugdebug(
'Received amcl pose')
808 def _feedbackCallback(self, msg):
809 self.
debugdebug(
'Received action feedback message')
810 self.
feedbackfeedback = msg.feedback
813 def _setInitialPose(self):
814 msg = PoseWithCovarianceStamped()
816 msg.header.frame_id = self.
initial_poseinitial_pose.header.frame_id
817 msg.header.stamp = self.
initial_poseinitial_pose.header.stamp
818 self.
infoinfo(
'Publishing Initial Pose')
823 self.get_logger().info(msg)
827 self.get_logger().warn(msg)
830 def error(self, msg):
831 self.get_logger().error(msg)
834 def debug(self, msg):
835 self.get_logger().debug(msg)
def clearAllCostmaps(self)
def _smoothPathImpl(self, path, smoother_id='', max_duration=2.0, check_for_collision=False)
def smoothPath(self, path, smoother_id='', max_duration=2.0, check_for_collision=False)
compute_path_to_pose_client
def getPath(self, start, goal, planner_id='', use_start=False)
def goToPose(self, pose, behavior_tree='')
def followWaypoints(self, poses)
def dockRobotByID(self, dock_id, nav_to_dock=True)
def clearCostmapAroundRobot(self, float reset_distance)
def getLocalCostmap(self)
clear_costmap_except_region_srv
def _getPathThroughPosesImpl(self, start, goals, planner_id='', use_start=False)
def getPathThroughPoses(self, start, goals, planner_id='', use_start=False)
def waitUntilNav2Active(self, navigator='bt_navigator', localizer='amcl')
def lifecycleStartup(self)
def goThroughPoses(self, poses, behavior_tree='')
follow_gps_waypoints_client
def clearCostmapAroundPose(self, PoseStamped pose, float reset_distance)
def changeMap(self, map_filepath)
def undockRobot(self, dock_type='')
clear_costmap_around_robot_srv
def _waitForInitialPose(self)
def clearLocalCostmap(self)
def clearGlobalCostmap(self)
def _amclPoseCallback(self, msg)
clear_costmap_around_pose_srv
def _getPathImpl(self, start, goal, planner_id='', use_start=False)
def lifecycleShutdown(self)
def getGlobalCostmap(self)
def clearCostmapExceptRegion(self, float reset_distance)
def _waitForNodeToActivate(self, node_name)
def followPath(self, path, controller_id='', goal_checker_id='')
compute_path_through_poses_client
def _feedbackCallback(self, msg)
def followGpsWaypoints(self, gps_poses)
def _setInitialPose(self)
def setInitialPose(self, initial_pose)
def dockRobotByPose(self, dock_pose, dock_type, nav_to_dock=True)