Simple Commander API

概述

Nav2 Simple (Python3) Commander 的目标是为 Python3 用户提供“导航作为库”功能。我们提供了一个 API,可为您处理所有 ROS 2 和 Action Server 任务,以便您可以专注于构建利用 Nav2 功能的应用程序(在您使用您选择的插件对其进行配置后)。我们还为您提供了 API 使用的演示和示例,以在 nav2_simple_commander 包中构建自主移动机器人的常见基本功能。

下面显示了一个简单的演示。注意​​:goToPose()goThroughPoses()followWaypoints() 和类似函数都是 非阻塞 的,因此您可以在单线程应用程序中接收和处理反馈。因此,在等待任务完成时,需要使用 while not nav.isTaskComplete() 设计来轮询导航完成情况的变化,如果没有完成您的应用程序感兴趣的一些任务(如处理反馈、使用机器人正在收集的数据执行某些操作或检查故障)。

您可以使用这个简单的命令来抢占相同类型的命令(例如,您可以使用另一个 goToPose() 抢占 goToPose()),但如果在 goToPose()goThroughPoses()followWaypoints() 之间切换,则必须明确取消当前命令并发出新命令。

from nav2_simple_commander.robot_navigator import BasicNavigator
import rclpy

rclpy.init()
nav = BasicNavigator()

# ...

nav.setInitialPose(init_pose)
nav.waitUntilNav2Active() # if autostarted, else use lifecycleStartup()

# ...

path = nav.getPath(init_pose, goal_pose)
smoothed_path = nav.smoothPath(path)

# ...

nav.goToPose(goal_pose)
while not nav.isTaskComplete():
  feedback = nav.getFeedback()
  if feedback.navigation_duration > 600:
    nav.cancelTask()

# ...

result = nav.getResult()
if result == TaskResult.SUCCEEDED:
    print('Goal succeeded!')
elif result == TaskResult.CANCELED:
    print('Goal was canceled!')
elif result == TaskResult.FAILED:
    print('Goal failed!')

Commander API

基本导航器提供的方法如下所示,包括输入和预期返回值。

如果服务器发生故障,它可能会抛出异常或返回 None 对象,因此请确保在 try/catch 中正确包装导航调用并检查返回值是否为 None 类型。

截至 2023 年 9 月的新功能:简单导航器构造函数将接受 namespace 字段以支持多机器人应用程序或命名空间 Nav2 启动。

Robot Navigator Method

Description

setInitialPose(initial_pose)

Sets the initial pose (PoseStamped) of the robot to localization.

goThroughPoses(poses, behavior_tree=’’)

Requests the robot to drive through a set of poses (list of PoseStamped).

goToPose(pose, behavior_tree=’’)

Requests the robot to drive to a pose (PoseStamped).

followWaypoints(poses)

Requests the robot to follow a set of waypoints (list of PoseStamped). This will execute the chosen TaskExecutor plugin at each pose.

followPath(path, controller_id=’’, goal_checker_id=’’)

Requests the robot to follow a path from a starting to a goal PoseStamped, nav_msgs/Path.

spin(spin_dist=1.57, time_allowance=10)

Requests the robot to performs an in-place rotation by a given angle.

driveOnHeading(dist=0.15, speed=0.025, time_allowance=10)

Requests the robot to drive on heading by a given distance.

backup(backup_dist=0.15, backup_speed=0.025, time_allowance=10)

Requests the robot to back up by a given distance.

assistedTeleop(time_allowance=30)

Requests the robot to run the assisted teleop action.

cancelTask()

Cancel an ongoing task, including route tasks.

isTaskComplete(trackingRoute=False)

Checks if task is complete yet, times out at 100ms. Returns True if completed and False if still going. If checking a route tracking task, set default argument to True.

getFeedback(trackingRoute=False)

Gets feedback from task, returns action server feedback msg. If getting feedback on a tracking task, set default argument to True.

getResult()

Gets final result of task, to be called after isTaskComplete returns True. Returns action server result msg.

getPath(start, goal, planner_id=’’, use_start=False)

Gets a path from a starting to a goal PoseStamped, nav_msgs/Path.

getPathThroughPoses(start, goals, planner_id=’’, use_start=False)

Gets a path through a starting to a set of goals, a list of PoseStamped, nav_msgs/Path.

dockRobot(dock_pose, dock_type)

Attempts to dock the robot at a given docking pose and type, without using docking database of known docks.

dockRobot(dock_id)

Attempts to dock the robot at a given dock ID in the database of known docks.

undockRobot(dock_type=””)

Undocks robot. If docking server instance was used to dock, type is not required.

smoothPath(path, smoother_id=’’, max_duration=2.0, check_for_collision=False)

Smooths a given path of type nav_msgs/Path.

changeMap(map_filepath)

Requests a change from the current map to map_filepath’s yaml.

clearAllCostmaps()

Clears both the global and local costmaps.

clearLocalCostmap()

Clears the local costmap.

clearGlobalCostmap()

Clears the global costmap.

getGlobalCostmap()

Returns the global costmap, nav2_msgs/Costmap.

getLocalCostmap()

Returns the local costmap, nav2_msgs/Costmap.

waitUntilNav2Active( navigator=’bt_navigator’, localizer=’amcl’)

Blocks until Nav2 is completely online and lifecycle nodes are in the active state. To be used in conjunction with autostart or external lifecycle bringup. Custom navigator and localizer nodes can be specified

lifecycleStartup()

Sends a request to all lifecycle management servers to bring them into the active state, to be used if autostart is False and you want this program to control Nav2’s lifecycle.

lifecycleShutdown()

Sends a request to all lifecycle management servers to shut them down.

destroyNode()

Releases the resources used by the object.

Costmap API

这是用于从堆栈获取 costmap 2d 消息的 Python3 API。它提供 costmap 2d C++ API 中的基本转换、获取/设置和处理语义。

Costmap Method

Description

getSizeInCellsX()

Get map width in cells.

getSizeInCellsY()

Get map height in cells.

getSizeInMetersX()

Get x axis map size in meters.

getSizeInMetersY()

Get y axis map size in meters.

getOriginX()

Get the origin x axis of the map [m].

getOriginY()

Get the origin y axis of the map [m].

getResolution()

Get map resolution [m/cell].

getGlobalFrameID()

Get global frame_id.

getCostmapTimestamp()

Get costmap timestamp.

getCostXY(mx, my)

Get the cost (np.uint8) of a cell in the costmap using mx (int) , my (int) of Map Coordinate.

getCostIdx(index)

Get the cost (np.uint8) of a cell in the costmap using index (int)

setCost(mx, my, cost)

Set the cost (np.uint8) of a cell in the costmap using mx (int) , my (int) of Map Coordinate.

mapToWorld(mx, my)

Get the wx (float) [m], wy (float) [m] of world coordinate XY using mx (int), my (int) of map coordinate XY

worldToMapValidated(wx, wy)

Get the mx (int), my (int) of map coordinate XY using wx (float) [m], wy (float) [m] of world coordinate XY. If wx wy coordinates are invalid, (None,None) is returned.

getIndex(mx, my)

Get the index (int) of the cell using mx (int), my (int) of map coordinate XY

Footprint Collision Checker API

这是足迹碰撞检查器的 Python3 API。 它提供了操作坐标所需的方法 并计算给定地图中足迹的成本。

Footprint Collision Checker Method

Description

footprintCost(footprint)

Checks the footprint (Polygon) for collision at its implicit provided coordinate pose.

lineCost(x0, x1, y0, y1, step_size=0.5)

Iterate over all the points along a line and check for collision. The line is defined by x0, y0, x1, y1, step_size (int) or (float).

worldToMapValidated(wx, wy)

Get the mx (int), my (int) of map coordinate XY using wx (float) [m], wy (float) [m] of world coordinate XY. If wx wy coordinates are invalid, (None,None) is returned. Returns None if costmap is not defined yet through (setCostmap(costmap)).

pointCost(x, y)

Get the cost of a point in the costmap using map coordinates XY. (int)

setCostmap(costmap)

Specify which costmap to use with the footprint collision checker. (PyCostmap2D)

footprintCostAtPose(x, y, theta, footprint)

Get the cost of a footprint at a specific Pose in map coordinates. x, y, theta (float) footprint (Polygon).

示例和演示

所有这些都可以在 package.

Alternative text

nav2_simple_commander 有几个示例,重点介绍了用户可用的 API 函数:

  • example_nav_to_pose.py - 演示导航器的导航姿势功能,以及许多辅助方法。

  • example_nav_through_poses.py - 演示导航器的导航姿势功能,以及许多辅助方法。

  • example_waypoint_follower.py - 演示导航器的航点跟踪功能,以及许多辅助方法。

  • example_follow_path.py - 演示导航器的路径跟踪功能,以及许多辅助方法,如路径平滑。

  • example_assisted_teleop.py - 演示导航器的辅助远距操作功能。

nav2_simple_commander 有几个演示,重点介绍了几个可以使用 API 构建的简单自主应用程序:

  • demo_security.py - 一个简单的安全机器人应用程序,展示如何使用 Navigate Through Poses 让机器人无限期地遵循安全路线进行巡逻。

  • demo_picking.py - 一个简单的物品挑选应用程序,展示如何让机器人驾驶到仓库中的特定货架来挑选物品,或者让一个人将物品放入篮子中,然后使用 Navigate To Pose 将其运送到目的地进行运输。

  • demo_inspection.py - 一个简单的货架检查应用程序,展示如何使用 Waypoint Follower 和任务执行器对货架进行拍照、RFID 扫描等,以分析当前货架状态并定位仓库中的物品。