Function rc_mav_send_gps_raw_int#
Defined in File mavlink_udp_helpers.h
Function Documentation#
-
int rc_mav_send_gps_raw_int(int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t fix_type, uint8_t satellites_visible, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc)#
Packs and sends a packet of type MAVLINK_MSG_ID_GPS_RAW_INT.
- Parameters:
lat – [in] Latitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
lon – [in] Longitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
alt – [in] Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
eph – [in] GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
epv – [in] GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
vel – [in] GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
cog – [in] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
fix_type – [in] See the GPS_FIX_TYPE enum.
satellites_visible – [in] Number of satellites visible. If unknown, set to 255
alt_ellipsoid – [in] Altitude (above WGS84, EGM96 ellipsoid), in meters * 1000 (positive for up).
h_acc – [in] Position uncertainty in meters * 1000 (positive for up).
v_acc – [in] Altitude uncertainty in meters * 1000 (positive for up).
vel_acc – [in] Speed uncertainty in meters * 1000 (positive for up).
hdg_acc – [in] Heading / track uncertainty in degrees * 1e5.
- Returns:
0 on success, -1 on failure