auv_msgs/NavSts Message

File: auv_msgs/NavSts.msg

Raw Message Definition

# Sent by the navigator at 5-10 Hz.

Header  header

DecimalLatLon global_position
DecimalLatLon origin

# NED position and altitude in metres. 
NED position
float32 altitude

# Body velocities in metres/sec.
geometry_msgs/Point body_velocity

# Orientation and orientation rate are in radians and radians/sec
RPY orientation
RPY orientation_rate

# Variances for position and orientation
NED position_variance
RPY orientation_variance

# Status and associated constants (flags)
uint8 status
uint8 STATUS_FAULT = 0
uint8 STATUS_LOCAL_FRAME_OK = 1
uint8 STATUS_GLOBAL_FRAME_OK = 2
uint8 STATUS_POSITION_OK = 3
uint8 STATUS_VELOCITY_OK = 4
uint8 STATUS_ESTIMATION_ERROR_OK  = 8
uint8 STATUS_ALL_OK = 15

Compact Message Definition

uint8 STATUS_FAULT=0
uint8 STATUS_LOCAL_FRAME_OK=1
uint8 STATUS_GLOBAL_FRAME_OK=2
uint8 STATUS_POSITION_OK=3
uint8 STATUS_VELOCITY_OK=4
uint8 STATUS_ESTIMATION_ERROR_OK=8
uint8 STATUS_ALL_OK=15
std_msgs/Header header
auv_msgs/DecimalLatLon global_position
auv_msgs/DecimalLatLon origin
auv_msgs/NED position
float32 altitude
geometry_msgs/Point body_velocity
auv_msgs/RPY orientation
auv_msgs/RPY orientation_rate
auv_msgs/NED position_variance
auv_msgs/RPY orientation_variance
uint8 status