File: mavros_msgs/SetMavFrame.srv
Raw Message Definition
# Set MAV_FRAME for setpoints
# [[[cog:
# from pymavlink.dialects.v20 import common
#
# def decl_enum(ename, pfx='', bsz=8):
# enum = sorted(common.enums[ename].items())
# enum.pop() # remove ENUM_END
#
# cog.outl("# " + ename)
# for k, e in enum:
# sn = e.name[len(ename) + 1:]
# l = "uint{bsz} {pfx}{sn} = {k}".format(**locals())
# if e.description:
# l += ' ' * (40 - len(l)) + ' # ' + e.description
# cog.outl(l)
#
# decl_enum('MAV_FRAME', 'FRAME_')
# ]]]
# MAV_FRAME
uint8 FRAME_GLOBAL = 0 # Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)
uint8 FRAME_LOCAL_NED = 1 # Local coordinate frame, Z-up (x: north, y: east, z: down).
uint8 FRAME_MISSION = 2 # NOT a coordinate frame, indicates a mission command.
uint8 FRAME_GLOBAL_RELATIVE_ALT = 3 # Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.
uint8 FRAME_LOCAL_ENU = 4 # Local coordinate frame, Z-down (x: east, y: north, z: up)
uint8 FRAME_GLOBAL_INT = 5 # Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL)
uint8 FRAME_GLOBAL_RELATIVE_ALT_INT = 6 # Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location.
uint8 FRAME_LOCAL_OFFSET_NED = 7 # Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.
uint8 FRAME_BODY_NED = 8 # Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.
uint8 FRAME_BODY_OFFSET_NED = 9 # Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.
uint8 FRAME_GLOBAL_TERRAIN_ALT = 10 # Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
uint8 FRAME_GLOBAL_TERRAIN_ALT_INT = 11 # Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
# [[[end]]] (checksum: e1f224cdf07c92a4457f1a880abdc0ff)
uint8 mav_frame
---
bool success
Compact Message Definition
uint8 FRAME_GLOBAL=0
uint8 FRAME_LOCAL_NED=1
uint8 FRAME_MISSION=2
uint8 FRAME_GLOBAL_RELATIVE_ALT=3
uint8 FRAME_LOCAL_ENU=4
uint8 FRAME_GLOBAL_INT=5
uint8 FRAME_GLOBAL_RELATIVE_ALT_INT=6
uint8 FRAME_LOCAL_OFFSET_NED=7
uint8 FRAME_BODY_NED=8
uint8 FRAME_BODY_OFFSET_NED=9
uint8 FRAME_GLOBAL_TERRAIN_ALT=10
uint8 FRAME_GLOBAL_TERRAIN_ALT_INT=11
uint8 mav_frame
bool success