File: asctec_hl_comm/GpsCustom.msg
Raw Message Definition
# Navigation Satellite fix for any Global Navigation Satellite System
#
# Specified using the WGS 84 reference ellipsoid
# Header specifies ROS time and frame of reference for this fix.
Header header
# satellite fix status information
sensor_msgs/NavSatStatus status
# Latitude [degrees]. Positive is north of equator; negative is south.
float64 latitude
# Longitude [degrees]. Positive is east of prime meridian; negative is west.
float64 longitude
# Altitude [m]. Positive is above the WGS 84 ellipsoid.
float64 altitude
# Position covariance [m^2] defined relative to a tangential plane
# through the reported position. The components are East, North, and
# Up (ENU), in row-major order.
#
# Beware: this coordinate system exhibits singularities at the poles.
float64[9] position_covariance
uint8 position_covariance_type
float64 pressure_height
float64 velocity_x
float64 velocity_y
float64[4] velocity_covariance
Compact Message Definition
std_msgs/Header header
sensor_msgs/NavSatStatus status
float64 latitude
float64 longitude
float64 altitude
float64[9] position_covariance
uint8 position_covariance_type
float64 pressure_height
float64 velocity_x
float64 velocity_y
float64[4] velocity_covariance