mbf_msgs/CheckPose Service

File: mbf_msgs/CheckPose.srv

Raw Message Definition

uint8                      LOCAL_COSTMAP  = 1
uint8                      GLOBAL_COSTMAP = 2

geometry_msgs/PoseStamped  pose              # the pose to be checked after transforming to costmap frame
float32                    safety_dist       # minimum distance allowed to the closest obstacle
float32                    lethal_cost_mult  # cost multiplier for cells marked as lethal obstacle (zero is ignored)
float32                    inscrib_cost_mult # cost multiplier for cells marked as inscribed obstacle (zero is ignored)
float32                    unknown_cost_mult # cost multiplier for cells marked as unknown space (zero is ignored)
uint8                      costmap           # costmap in which to check the pose
bool                       current_pose      # check current robot pose instead (ignores pose field)
---
uint8                      FREE      =  0    # robot is completely in traversable space
uint8                      INSCRIBED =  1    # robot is partially in inscribed space
uint8                      LETHAL    =  2    # robot is partially in collision
uint8                      UNKNOWN   =  3    # robot is partially in unknown space
uint8                      OUTSIDE   =  4    # robot is partially outside the map

uint8                      state             # pose state: FREE, INFLATED, LETHAL, UNKNOWN or OUTSIDE
uint32                     cost              # total cost of all cells within footprint padded by safety_dist

Compact Message Definition

uint8 LOCAL_COSTMAP=1
uint8 GLOBAL_COSTMAP=2
geometry_msgs/PoseStamped pose
float32 safety_dist
float32 lethal_cost_mult
float32 inscrib_cost_mult
float32 unknown_cost_mult
uint8 costmap
bool current_pose

uint8 FREE=0
uint8 INSCRIBED=1
uint8 LETHAL=2
uint8 UNKNOWN=3
uint8 OUTSIDE=4
uint8 state
uint32 cost