Function rc_mav_send_set_position_target_global_int#
Defined in File mavlink_udp_helpers.h
Function Documentation#
-
int rc_mav_send_set_position_target_global_int(int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate, uint16_t type_mask, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame)#
Packs and sends a packet of type MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT.
- Parameters:
lat_int – [in] X Position in WGS84 frame in 1e7 * degrees
lon_int – [in] Y Position in WGS84 frame in 1e7 * degrees
alt – [in] Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
vx – [in] X velocity in NED frame in m/s
vy – [in] Y velocity in NED frame in m/s
vz – [in] Z velocity in NED frame in m/s
afx – [in] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter/s^2 or N
afy – [in] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter/s^2 or N
afz – [in] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter/s^2 or N
yaw – [in] yaw setpoint in rad
yaw_rate – [in] yaw rate setpoint in rad/s
type_mask – [in] Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
target_system – [in] System ID
target_component – [in] Component ID
coordinate_frame – [in] Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
- Returns:
0 on success, -1 on failure