nav2_msgs: Kilted
  • Links
    • Rosindex
    • Repository
  • Message Definitions
    • BehaviorTreeLog
    • BehaviorTreeStatusChange
    • CollisionDetectorState
    • CollisionMonitorState
    • Costmap
    • CostmapFilterInfo
    • CostmapMetaData
    • CostmapUpdate
    • EdgeCost
    • Particle
    • ParticleCloud
    • Route
    • RouteEdge
    • RouteNode
    • SpeedLimit
    • Trajectory
    • TrajectoryPoint
    • VoxelGrid
    • WaypointStatus
  • Service Definitions
    • ClearCostmapAroundRobot
    • ClearCostmapExceptRegion
    • ClearEntireCostmap
    • DynamicEdges
    • GetCostmap
    • GetCosts
    • IsPathValid
    • LoadMap
    • ManageLifecycleNodes
    • ReloadDockDatabase
    • SaveMap
    • SetInitialPose
    • SetRouteGraph
  • Action Definitions
    • AssistedTeleop
    • BackUp
    • ComputeAndTrackRoute
    • ComputePathThroughPoses
    • ComputePathToPose
    • ComputeRoute
    • DockRobot
    • DriveOnHeading
    • DummyBehavior
    • FollowGPSWaypoints
    • FollowPath
    • FollowWaypoints
    • NavigateThroughPoses
    • NavigateToPose
    • SmoothPath
    • Spin
    • UndockRobot
    • Wait
  • Standard Documents
    • README
      • nav2_msgs
    • PACKAGE
    • CHANGELOG
  • Index
nav2_msgs: Kilted
  • Action Definitions
  • NavigateToPose
  • View page source

NavigateToPose

This is a ROS action definition.

Source

#goal definition
geometry_msgs/PoseStamped pose
string behavior_tree
---
#result definition

# Error codes
# Note: The expected priority order of the errors should match the message order
uint16 NONE=0
uint16 UNKNOWN=9000
uint16 FAILED_TO_LOAD_BEHAVIOR_TREE=9001
uint16 TF_ERROR=9002
uint16 TIMEOUT=9003

uint16 error_code
string error_msg
---
#feedback definition
geometry_msgs/PoseStamped current_pose
builtin_interfaces/Duration navigation_time
builtin_interfaces/Duration estimated_time_remaining
int16 number_of_recoveries
float32 distance_remaining
Previous Next

© Copyright The <nav2_msgs> Contributors. License: Apache-2.0.

Built with Sphinx using a theme provided by Read the Docs.