Documentation ¶
Index ¶
- Constants
- type Attitude
- type AttitudeQuaternion
- type AttitudeSetpointExternal
- type AuthKey
- type BatteryStatus
- type ChangeOperatorControl
- type ChangeOperatorControlAck
- type CommandAck
- type CommandLong
- type DataStream
- type DataTransmissionHandshake
- type Debug
- type DebugVect
- type DistanceSensor
- type EncapsulatedData
- type FileTransferDirList
- type FileTransferRes
- type FileTransferStart
- type GlobalPositionInt
- type GlobalPositionSetpointExternalInt
- type GlobalPositionSetpointInt
- type GlobalVisionPositionEstimate
- type Gps2Raw
- type Gps2Rtk
- type GpsGlobalOrigin
- type GpsInjectData
- type GpsRawInt
- type GpsRtk
- type GpsStatus
- type Heartbeat
- type HighresImu
- type HilControls
- type HilGps
- type HilOpticalFlow
- type HilRcInputsRaw
- type HilSensor
- type HilState
- type HilStateQuaternion
- type LocalNedPositionSetpointExternal
- type LocalPositionNed
- type LocalPositionNedSystemGlobalOffset
- type LocalPositionSetpoint
- type LogData
- type LogEntry
- type LogErase
- type LogRequestData
- type LogRequestEnd
- type LogRequestList
- type MAVLinkMessage
- type MAVLinkPacket
- type ManualControl
- type ManualSetpoint
- type MemoryVect
- type MissionAck
- type MissionClearAll
- type MissionCount
- type MissionCurrent
- type MissionItem
- type MissionItemReached
- type MissionRequest
- type MissionRequestList
- type MissionRequestPartialList
- type MissionSetCurrent
- type MissionWritePartialList
- type NamedValueFloat
- type NamedValueInt
- type NavControllerOutput
- type OmnidirectionalFlow
- type OpticalFlow
- type ParamRequestList
- type ParamRequestRead
- type ParamSet
- type ParamValue
- type Ping
- type PowerStatus
- type RadioStatus
- type RawImu
- type RawPressure
- type RcChannels
- type RcChannelsOverride
- type RcChannelsRaw
- type RcChannelsScaled
- type RequestDataStream
- type RollPitchYawRatesThrustSetpoint
- type RollPitchYawSpeedThrustSetpoint
- type RollPitchYawThrustSetpoint
- type SafetyAllowedArea
- type SafetySetAllowedArea
- type ScaledImu
- type ScaledImu2
- type ScaledPressure
- type SerialControl
- type ServoOutputRaw
- type SetGlobalPositionSetpointInt
- type SetGpsGlobalOrigin
- type SetLocalPositionSetpoint
- type SetMode
- type SetQuadMotorsSetpoint
- type SetQuadSwarmLedRollPitchYawThrust
- type SetQuadSwarmRollPitchYawThrust
- type SetRollPitchYawSpeedThrust
- type SetRollPitchYawThrust
- type Setpoint6Dof
- type Setpoint8Dof
- type SimState
- type StateCorrection
- type Statustext
- type SysStatus
- type SystemTime
- type TerrainCheck
- type TerrainData
- type TerrainReport
- type TerrainRequest
- type VfrHud
- type ViconPositionEstimate
- type VisionPositionEstimate
- type VisionSpeedEstimate
Constants ¶
const ( MAV_AUTOPILOT_GENERIC = 0 // Generic autopilot, full support for everything | MAV_AUTOPILOT_PIXHAWK = 1 // PIXHAWK autopilot, http://pixhawk.ethz.ch | MAV_AUTOPILOT_SLUGS = 2 // SLUGS autopilot, http://slugsuav.soe.ucsc.edu | MAV_AUTOPILOT_ARDUPILOTMEGA = 3 // ArduPilotMega / ArduCopter, http://diydrones.com | MAV_AUTOPILOT_OPENPILOT = 4 // OpenPilot, http://openpilot.org | MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5 // Generic autopilot only supporting simple waypoints | MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6 // Generic autopilot supporting waypoints and other simple navigation commands | MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7 // Generic autopilot supporting the full mission command set | MAV_AUTOPILOT_INVALID = 8 // No valid autopilot, e.g. a GCS or other MAVLink component | MAV_AUTOPILOT_PPZ = 9 // PPZ UAV - http://nongnu.org/paparazzi | MAV_AUTOPILOT_UDB = 10 // UAV Dev Board | MAV_AUTOPILOT_FP = 11 // FlexiPilot | MAV_AUTOPILOT_PX4 = 12 // PX4 Autopilot - http://pixhawk.ethz.ch/px4/ | MAV_AUTOPILOT_SMACCMPILOT = 13 // SMACCMPilot - http://smaccmpilot.org | MAV_AUTOPILOT_AUTOQUAD = 14 // AutoQuad -- http://autoquad.org | MAV_AUTOPILOT_ARMAZILA = 15 // Armazila -- http://armazila.com | MAV_AUTOPILOT_AEROB = 16 // Aerob -- http://aerob.ru | MAV_AUTOPILOT_ENUM_END = 17 // | )
MAV_AUTOPILOT Micro air vehicle / autopilot classes. This identifies the individual model.
const ( MAV_TYPE_GENERIC = 0 // Generic micro air vehicle. | MAV_TYPE_FIXED_WING = 1 // Fixed wing aircraft. | MAV_TYPE_QUADROTOR = 2 // Quadrotor | MAV_TYPE_COAXIAL = 3 // Coaxial helicopter | MAV_TYPE_HELICOPTER = 4 // Normal helicopter with tail rotor. | MAV_TYPE_ANTENNA_TRACKER = 5 // Ground installation | MAV_TYPE_GCS = 6 // Operator control unit / ground control station | MAV_TYPE_AIRSHIP = 7 // Airship, controlled | MAV_TYPE_FREE_BALLOON = 8 // Free balloon, uncontrolled | MAV_TYPE_ROCKET = 9 // Rocket | MAV_TYPE_GROUND_ROVER = 10 // Ground rover | MAV_TYPE_SURFACE_BOAT = 11 // Surface vessel, boat, ship | MAV_TYPE_SUBMARINE = 12 // Submarine | MAV_TYPE_HEXAROTOR = 13 // Hexarotor | MAV_TYPE_OCTOROTOR = 14 // Octorotor | MAV_TYPE_TRICOPTER = 15 // Octorotor | MAV_TYPE_FLAPPING_WING = 16 // Flapping wing | MAV_TYPE_KITE = 17 // Flapping wing | MAV_TYPE_ONBOARD_CONTROLLER = 18 // Onboard companion controller | MAV_TYPE_ENUM_END = 19 // | )
MAV_TYPE
const ( MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 // 0b00000001 Reserved for future use. | MAV_MODE_FLAG_TEST_ENABLED = 2 // 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | MAV_MODE_FLAG_AUTO_ENABLED = 4 // 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | MAV_MODE_FLAG_GUIDED_ENABLED = 8 // 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | MAV_MODE_FLAG_STABILIZE_ENABLED = 16 // 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | MAV_MODE_FLAG_HIL_ENABLED = 32 // 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 // 0b01000000 remote control input is enabled. | MAV_MODE_FLAG_SAFETY_ARMED = 128 // 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | MAV_MODE_FLAG_ENUM_END = 129 // | )
MAV_MODE_FLAG These flags encode the MAV mode.
const ( MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1 // Eighth bit: 00000001 | MAV_MODE_FLAG_DECODE_POSITION_TEST = 2 // Seventh bit: 00000010 | MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4 // Sixt bit: 00000100 | MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8 // Fifth bit: 00001000 | MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16 // Fourth bit: 00010000 | MAV_MODE_FLAG_DECODE_POSITION_HIL = 32 // Third bit: 00100000 | MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64 // Second bit: 01000000 | MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128 // First bit: 10000000 | MAV_MODE_FLAG_DECODE_POSITION_ENUM_END = 129 // | )
MAV_MODE_FLAG_DECODE_POSITION These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.
const ( MAV_GOTO_DO_HOLD = 0 // Hold at the current position. | MAV_GOTO_DO_CONTINUE = 1 // Continue with the next item in mission execution. | MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2 // Hold at the current position of the system | MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3 // Hold at the position specified in the parameters of the DO_HOLD action | MAV_GOTO_ENUM_END = 4 // | )
MAV_GOTO Override command, pauses current mission execution and moves immediately to a position
const ( MAV_MODE_PREFLIGHT = 0 // System is not ready to fly, booting, calibrating, etc. No flag is set. | MAV_MODE_MANUAL_DISARMED = 64 // System is allowed to be active, under manual (RC) control, no stabilization | MAV_MODE_TEST_DISARMED = 66 // UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | MAV_MODE_STABILIZE_DISARMED = 80 // System is allowed to be active, under assisted RC control. | MAV_MODE_GUIDED_DISARMED = 88 // System is allowed to be active, under autonomous control, manual setpoint | MAV_MODE_AUTO_DISARMED = 92 // System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | MAV_MODE_MANUAL_ARMED = 192 // System is allowed to be active, under manual (RC) control, no stabilization | MAV_MODE_TEST_ARMED = 194 // UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | MAV_MODE_STABILIZE_ARMED = 208 // System is allowed to be active, under assisted RC control. | MAV_MODE_GUIDED_ARMED = 216 // System is allowed to be active, under autonomous control, manual setpoint | MAV_MODE_AUTO_ARMED = 220 // System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | MAV_MODE_ENUM_END = 221 // | )
MAV_MODE These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it
simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override.
const ( MAV_STATE_UNINIT = 0 // Uninitialized system, state is unknown. | MAV_STATE_BOOT = 1 // System is booting up. | MAV_STATE_CALIBRATING = 2 // System is calibrating and not flight-ready. | MAV_STATE_STANDBY = 3 // System is grounded and on standby. It can be launched any time. | MAV_STATE_ACTIVE = 4 // System is active and might be already airborne. Motors are engaged. | MAV_STATE_CRITICAL = 5 // System is in a non-normal flight mode. It can however still navigate. | MAV_STATE_EMERGENCY = 6 // System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | MAV_STATE_POWEROFF = 7 // System just initialized its power-down sequence, will shut down now. | MAV_STATE_ENUM_END = 8 // | )
MAV_STATE
const ( MAV_COMP_ID_ALL = 0 // | MAV_COMP_ID_CAMERA = 100 // | MAV_COMP_ID_SERVO1 = 140 // | MAV_COMP_ID_SERVO2 = 141 // | MAV_COMP_ID_SERVO3 = 142 // | MAV_COMP_ID_SERVO4 = 143 // | MAV_COMP_ID_SERVO5 = 144 // | MAV_COMP_ID_SERVO6 = 145 // | MAV_COMP_ID_SERVO7 = 146 // | MAV_COMP_ID_SERVO8 = 147 // | MAV_COMP_ID_SERVO9 = 148 // | MAV_COMP_ID_SERVO10 = 149 // | MAV_COMP_ID_SERVO11 = 150 // | MAV_COMP_ID_SERVO12 = 151 // | MAV_COMP_ID_SERVO13 = 152 // | MAV_COMP_ID_SERVO14 = 153 // | MAV_COMP_ID_MAPPER = 180 // | MAV_COMP_ID_MISSIONPLANNER = 190 // | MAV_COMP_ID_PATHPLANNER = 195 // | MAV_COMP_ID_IMU = 200 // | MAV_COMP_ID_IMU_2 = 201 // | MAV_COMP_ID_IMU_3 = 202 // | MAV_COMP_ID_GPS = 220 // | MAV_COMP_ID_UDP_BRIDGE = 240 // | MAV_COMP_ID_UART_BRIDGE = 241 // | MAV_COMP_ID_SYSTEM_CONTROL = 250 // | MAV_COMPONENT_ENUM_END = 251 // | )
MAV_COMPONENT
const ( MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 // 0x01 3D gyro | MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 // 0x02 3D accelerometer | MAV_SYS_STATUS_SENSOR_3D_MAG = 4 // 0x04 3D magnetometer | MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 // 0x08 absolute pressure | MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 // 0x10 differential pressure | MAV_SYS_STATUS_SENSOR_GPS = 32 // 0x20 GPS | MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 // 0x40 optical flow | MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 // 0x80 computer vision position | MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 // 0x100 laser based position | MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 // 0x200 external ground truth (Vicon or Leica) | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 // 0x400 3D angular rate control | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 // 0x800 attitude stabilization | MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 // 0x1000 yaw position | MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 // 0x2000 z/altitude control | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 // 0x4000 x/y position control | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 // 0x8000 motor outputs / control | MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 // 0x10000 rc receiver | MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 // 0x20000 2nd 3D gyro | MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 // 0x40000 2nd 3D accelerometer | MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 // 0x80000 2nd 3D magnetometer | MAV_SYS_STATUS_GEOFENCE = 1048576 // 0x100000 geofence | MAV_SYS_STATUS_AHRS = 2097152 // 0x200000 AHRS subsystem health | MAV_SYS_STATUS_TERRAIN = 4194304 // 0x400000 Terrain subsystem health | MAV_SYS_STATUS_SENSOR_ENUM_END = 4194305 // | )
MAV_SYS_STATUS_SENSOR These encode the sensors whose status is sent as part of the SYS_STATUS message.
const ( MAV_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) | MAV_FRAME_LOCAL_NED = 1 // Local coordinate frame, Z-up (x: north, y: east, z: down). | MAV_FRAME_MISSION = 2 // NOT a coordinate frame, indicates a mission command. | MAV_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. | MAV_FRAME_LOCAL_ENU = 4 // Local coordinate frame, Z-down (x: east, y: north, z: up) | MAV_FRAME_GLOBAL_INT = 5 // Global coordinate frame with some fields as scaled integers, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL). Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations. | MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6 // Global coordinate frame with some fields as scaled integers, 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. Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations. | MAV_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. | MAV_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. | MAV_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. | MAV_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, second value / y: longitude, third value / z: positive altitude with 0 being at ground level in terrain model. | MAV_FRAME_ENUM_END = 11 // | )
MAV_FRAME
const ( MAVLINK_DATA_STREAM_IMG_JPEG = 1 // | MAVLINK_DATA_STREAM_IMG_BMP = 2 // | MAVLINK_DATA_STREAM_IMG_RAW8U = 3 // | MAVLINK_DATA_STREAM_IMG_RAW32U = 4 // | MAVLINK_DATA_STREAM_IMG_PGM = 5 // | MAVLINK_DATA_STREAM_IMG_PNG = 6 // | MAVLINK_DATA_STREAM_TYPE_ENUM_END = 7 // | )
MAVLINK_DATA_STREAM_TYPE
const ( FENCE_ACTION_NONE = 0 // Disable fenced mode | FENCE_ACTION_GUIDED = 1 // Switched to guided mode to return point (fence point 0) | FENCE_ACTION_REPORT = 2 // Report fence breach, but don't take action | FENCE_ACTION_GUIDED_THR_PASS = 3 // Switched to guided mode to return point (fence point 0) with manual throttle control | FENCE_ACTION_ENUM_END = 4 // | )
FENCE_ACTION
const ( FENCE_BREACH_NONE = 0 // No last fence breach | FENCE_BREACH_MINALT = 1 // Breached minimum altitude | FENCE_BREACH_MAXALT = 2 // Breached maximum altitude | FENCE_BREACH_BOUNDARY = 3 // Breached fence boundary | FENCE_BREACH_ENUM_END = 4 // | )
FENCE_BREACH
const ( MAV_MOUNT_MODE_RETRACT = 0 // Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | MAV_MOUNT_MODE_NEUTRAL = 1 // Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | MAV_MOUNT_MODE_MAVLINK_TARGETING = 2 // Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | MAV_MOUNT_MODE_RC_TARGETING = 3 // Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | MAV_MOUNT_MODE_GPS_POINT = 4 // Load neutral position and start to point to Lat,Lon,Alt | MAV_MOUNT_MODE_ENUM_END = 5 // | )
MAV_MOUNT_MODE Enumeration of possible mount operation modes
const ( MAV_CMD_NAV_WAYPOINT = 16 // Navigate to MISSION. | Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) | Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached) | 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. | Desired yaw angle at MISSION (rotary wing) | Latitude | Longitude | Altitude | MAV_CMD_NAV_LOITER_UNLIM = 17 // Loiter around this MISSION an unlimited amount of time | Empty | Empty | Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise | Desired yaw angle. | Latitude | Longitude | Altitude | MAV_CMD_NAV_LOITER_TURNS = 18 // Loiter around this MISSION for X turns | Turns | Empty | Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise | Desired yaw angle. | Latitude | Longitude | Altitude | MAV_CMD_NAV_LOITER_TIME = 19 // Loiter around this MISSION for X seconds | Seconds (decimal) | Empty | Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise | Desired yaw angle. | Latitude | Longitude | Altitude | MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 // Return to launch location | Empty | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_NAV_LAND = 21 // Land at location | Empty | Empty | Empty | Desired yaw angle. | Latitude | Longitude | Altitude | MAV_CMD_NAV_TAKEOFF = 22 // Takeoff from ground / hand | Minimum pitch (if airspeed sensor present), desired pitch without sensor | Empty | Empty | Yaw angle (if magnetometer present), ignored without magnetometer | Latitude | Longitude | Altitude | MAV_CMD_NAV_ROI = 80 // Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. | Region of intereset mode. (see MAV_ROI enum) | MISSION index/ target ID. (see MAV_ROI enum) | ROI index (allows a vehicle to manage multiple ROI's) | Empty | x the location of the fixed ROI (see MAV_FRAME) | y | z | MAV_CMD_NAV_PATHPLANNING = 81 // Control autonomous path planning on the MAV. | 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning | 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid | Empty | Yaw angle at goal, in compass degrees, [0..360] | Latitude/X of goal | Longitude/Y of goal | Altitude/Z of goal | MAV_CMD_NAV_SPLINE_WAYPOINT = 82 // Navigate to MISSION using a spline path. | Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) | Empty | Empty | Empty | Latitude/X of goal | Longitude/Y of goal | Altitude/Z of goal | MAV_CMD_NAV_GUIDED_ENABLE = 92 // hand control over to an external controller | On / Off (> 0.5f on) | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_NAV_LAST = 95 // NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration | Empty | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_CONDITION_DELAY = 112 // Delay mission state machine. | Delay in seconds (decimal) | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_CONDITION_CHANGE_ALT = 113 // Ascend/descend at rate. Delay mission state machine until desired altitude reached. | Descent / Ascend rate (m/s) | Empty | Empty | Empty | Empty | Empty | Finish Altitude | MAV_CMD_CONDITION_DISTANCE = 114 // Delay mission state machine until within desired distance of next NAV point. | Distance (meters) | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_CONDITION_YAW = 115 // Reach a certain target angle. | target angle: [0-360], 0 is north | speed during yaw change:[deg per second] | direction: negative: counter clockwise, positive: clockwise [-1,1] | relative offset or absolute angle: [ 1,0] | Empty | Empty | Empty | MAV_CMD_CONDITION_LAST = 159 // NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration | Empty | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_SET_MODE = 176 // Set system mode. | Mode, as defined by ENUM MAV_MODE | Custom mode - this is system specific, please refer to the individual autopilot specifications for details. | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_JUMP = 177 // Jump to the desired command in the mission list. Repeat this action only the specified number of times | Sequence number | Repeat count | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_CHANGE_SPEED = 178 // Change speed and/or throttle set points. | Speed type (0=Airspeed, 1=Ground Speed) | Speed (m/s, -1 indicates no change) | Throttle ( Percent, -1 indicates no change) | Empty | Empty | Empty | Empty | MAV_CMD_DO_SET_HOME = 179 // Changes the home location either to the current location or a specified location. | Use current (1=use current location, 0=use specified location) | Empty | Empty | Empty | Latitude | Longitude | Altitude | MAV_CMD_DO_SET_PARAMETER = 180 // Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. | Parameter number | Parameter value | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_SET_RELAY = 181 // Set a relay to a condition. | Relay number | Setting (1=on, 0=off, others possible depending on system hardware) | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_REPEAT_RELAY = 182 // Cycle a relay on and off for a desired number of cyles with a desired period. | Relay number | Cycle count | Cycle time (seconds, decimal) | Empty | Empty | Empty | Empty | MAV_CMD_DO_SET_SERVO = 183 // Set a servo to a desired PWM value. | Servo number | PWM (microseconds, 1000 to 2000 typical) | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_REPEAT_SERVO = 184 // Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. | Servo number | PWM (microseconds, 1000 to 2000 typical) | Cycle count | Cycle time (seconds) | Empty | Empty | Empty | MAV_CMD_DO_FLIGHTTERMINATION = 185 // Terminate flight immediately | Flight termination activated if > 0.5 | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_RALLY_LAND = 190 // Mission command to perform a landing from a rally point. | Break altitude (meters) | Landing speed (m/s) | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_GO_AROUND = 191 // Mission command to safely abort an autonmous landing. | Altitude (meters) | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_CONTROL_VIDEO = 200 // Control onboard camera system. | Camera ID (-1 for all) | Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw | Transmission mode: 0: video stream, >0: single images every n seconds (decimal) | Recording: 0: disabled, 1: enabled compressed, 2: enabled raw | Empty | Empty | Empty | MAV_CMD_DO_SET_ROI = 201 // Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. | Region of intereset mode. (see MAV_ROI enum) | MISSION index/ target ID. (see MAV_ROI enum) | ROI index (allows a vehicle to manage multiple ROI's) | Empty | x the location of the fixed ROI (see MAV_FRAME) | y | z | MAV_CMD_DO_DIGICAM_CONFIGURE = 202 // Mission command to configure an on-board camera controller system. | Modes: P, TV, AV, M, Etc | Shutter speed: Divisor number for one second | Aperture: F stop number | ISO number e.g. 80, 100, 200, Etc | Exposure type enumerator | Command Identity | Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) | MAV_CMD_DO_DIGICAM_CONTROL = 203 // Mission command to control an on-board camera controller system. | Session control e.g. show/hide lens | Zoom's absolute position | Zooming step value to offset zoom from the current position | Focus Locking, Unlocking or Re-locking | Shooting Command | Command Identity | Empty | MAV_CMD_DO_MOUNT_CONFIGURE = 204 // Mission command to configure a camera or antenna mount | Mount operation mode (see MAV_MOUNT_MODE enum) | stabilize roll? (1 = yes, 0 = no) | stabilize pitch? (1 = yes, 0 = no) | stabilize yaw? (1 = yes, 0 = no) | Empty | Empty | Empty | MAV_CMD_DO_MOUNT_CONTROL = 205 // Mission command to control a camera or antenna mount | pitch or lat in degrees, depending on mount mode. | roll or lon in degrees depending on mount mode | yaw or alt (in meters) depending on mount mode | reserved | reserved | reserved | MAV_MOUNT_MODE enum value | MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 // Mission command to set CAM_TRIGG_DIST for this flight | Camera trigger distance (meters) | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_FENCE_ENABLE = 207 // Mission command to enable the geofence | enable? (0=disable, 1=enable) | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_PARACHUTE = 208 // Mission command to trigger a parachute | action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.) | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_INVERTED_FLIGHT = 210 // Change to/from inverted flight | inverted (0=normal, 1=inverted) | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 // Mission command to control a camera or antenna mount, using a quaternion as reference. | q1 - quaternion param #1, w (1 in null-rotation) | q2 - quaternion param #2, x (0 in null-rotation) | q3 - quaternion param #3, y (0 in null-rotation) | q4 - quaternion param #4, z (0 in null-rotation) | Empty | Empty | Empty | MAV_CMD_DO_GUIDED_MASTER = 221 // set id of master controller | System ID | Component ID | Empty | Empty | Empty | Empty | Empty | MAV_CMD_DO_GUIDED_LIMITS = 222 // set limits for external control | timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout | absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit | absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit | horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit | Empty | Empty | Empty | MAV_CMD_DO_LAST = 240 // NOP - This command is only used to mark the upper limit of the DO commands in the enumeration | Empty | Empty | Empty | Empty | Empty | Empty | Empty | MAV_CMD_PREFLIGHT_CALIBRATION = 241 // Trigger calibration. This command will be only accepted if in pre-flight mode. | Gyro calibration: 0: no, 1: yes | Magnetometer calibration: 0: no, 1: yes | Ground pressure: 0: no, 1: yes | Radio calibration: 0: no, 1: yes | Accelerometer calibration: 0: no, 1: yes | Compass/Motor interference calibration: 0: no, 1: yes | Empty | MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 // Set sensor offsets. This command will be only accepted if in pre-flight mode. | Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer | X axis offset (or generic dimension 1), in the sensor's raw units | Y axis offset (or generic dimension 2), in the sensor's raw units | Z axis offset (or generic dimension 3), in the sensor's raw units | Generic dimension 4, in the sensor's raw units | Generic dimension 5, in the sensor's raw units | Generic dimension 6, in the sensor's raw units | MAV_CMD_PREFLIGHT_STORAGE = 245 // Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. | Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM | Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM | Reserved | Reserved | Empty | Empty | Empty | MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 // Request the reboot or shutdown of system components. | 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot. | 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer. | Reserved | Reserved | Empty | Empty | Empty | MAV_CMD_OVERRIDE_GOTO = 252 // Hold / continue the current action | MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan | MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position | MAV_FRAME coordinate frame of hold point | Desired yaw angle in degrees | Latitude / X position | Longitude / Y position | Altitude / Z position | MAV_CMD_MISSION_START = 300 // start running a mission | first_item: the first mission item to run | last_item: the last mission item to run (after this item is run, the mission ends) | MAV_CMD_COMPONENT_ARM_DISARM = 400 // Arms / Disarms a component | 1 to arm, 0 to disarm | MAV_CMD_START_RX_PAIR = 500 // Starts receiver pairing | 0:Spektrum | 0:Spektrum DSM2, 1:Spektrum DSMX | MAV_CMD_ENUM_END = 501 // | )
MAV_CMD Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data.
const ( MAV_DATA_STREAM_ALL = 0 // Enable all data streams | MAV_DATA_STREAM_RAW_SENSORS = 1 // Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | MAV_DATA_STREAM_EXTENDED_STATUS = 2 // Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | MAV_DATA_STREAM_RC_CHANNELS = 3 // Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | MAV_DATA_STREAM_RAW_CONTROLLER = 4 // Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | MAV_DATA_STREAM_POSITION = 6 // Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | MAV_DATA_STREAM_EXTRA1 = 10 // Dependent on the autopilot | MAV_DATA_STREAM_EXTRA2 = 11 // Dependent on the autopilot | MAV_DATA_STREAM_EXTRA3 = 12 // Dependent on the autopilot | MAV_DATA_STREAM_ENUM_END = 13 // | )
MAV_DATA_STREAM Data stream IDs. A data stream is not a fixed set of messages, but rather a
recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages.
const ( MAV_ROI_NONE = 0 // No region of interest. | MAV_ROI_WPNEXT = 1 // Point toward next MISSION. | MAV_ROI_WPINDEX = 2 // Point toward given MISSION. | MAV_ROI_LOCATION = 3 // Point toward fixed location. | MAV_ROI_TARGET = 4 // Point toward of given id. | MAV_ROI_ENUM_END = 5 // | )
MAV_ROI
The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI).
const ( MAV_CMD_ACK_OK = 1 // Command / mission item is ok. | MAV_CMD_ACK_ERR_FAIL = 2 // Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 // The system is refusing to accept this command from this source / communication partner. | MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 // Command or mission item is not supported, other commands would be accepted. | MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 // The coordinate frame of this command / mission item is not supported. | MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 // The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 // The X or latitude value is out of range. | MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 // The Y or longitude value is out of range. | MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 // The Z or altitude value is out of range. | MAV_CMD_ACK_ENUM_END = 10 // | )
MAV_CMD_ACK ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.
const ( MAV_PARAM_TYPE_UINT8 = 1 // 8-bit unsigned integer | MAV_PARAM_TYPE_INT8 = 2 // 8-bit signed integer | MAV_PARAM_TYPE_UINT16 = 3 // 16-bit unsigned integer | MAV_PARAM_TYPE_INT16 = 4 // 16-bit signed integer | MAV_PARAM_TYPE_UINT32 = 5 // 32-bit unsigned integer | MAV_PARAM_TYPE_INT32 = 6 // 32-bit signed integer | MAV_PARAM_TYPE_UINT64 = 7 // 64-bit unsigned integer | MAV_PARAM_TYPE_INT64 = 8 // 64-bit signed integer | MAV_PARAM_TYPE_REAL32 = 9 // 32-bit floating-point | MAV_PARAM_TYPE_REAL64 = 10 // 64-bit floating-point | MAV_PARAM_TYPE_ENUM_END = 11 // | )
MAV_PARAM_TYPE Specifies the datatype of a MAVLink parameter.
const ( MAV_RESULT_ACCEPTED = 0 // Command ACCEPTED and EXECUTED | MAV_RESULT_TEMPORARILY_REJECTED = 1 // Command TEMPORARY REJECTED/DENIED | MAV_RESULT_DENIED = 2 // Command PERMANENTLY DENIED | MAV_RESULT_UNSUPPORTED = 3 // Command UNKNOWN/UNSUPPORTED | MAV_RESULT_FAILED = 4 // Command executed, but failed | MAV_RESULT_ENUM_END = 5 // | )
MAV_RESULT result from a mavlink command
const ( MAV_MISSION_ACCEPTED = 0 // mission accepted OK | MAV_MISSION_ERROR = 1 // generic error / not accepting mission commands at all right now | MAV_MISSION_UNSUPPORTED_FRAME = 2 // coordinate frame is not supported | MAV_MISSION_UNSUPPORTED = 3 // command is not supported | MAV_MISSION_NO_SPACE = 4 // mission item exceeds storage space | MAV_MISSION_INVALID = 5 // one of the parameters has an invalid value | MAV_MISSION_INVALID_PARAM1 = 6 // param1 has an invalid value | MAV_MISSION_INVALID_PARAM2 = 7 // param2 has an invalid value | MAV_MISSION_INVALID_PARAM3 = 8 // param3 has an invalid value | MAV_MISSION_INVALID_PARAM4 = 9 // param4 has an invalid value | MAV_MISSION_INVALID_PARAM5_X = 10 // x/param5 has an invalid value | MAV_MISSION_INVALID_PARAM6_Y = 11 // y/param6 has an invalid value | MAV_MISSION_INVALID_PARAM7 = 12 // param7 has an invalid value | MAV_MISSION_INVALID_SEQUENCE = 13 // received waypoint out of sequence | MAV_MISSION_DENIED = 14 // not accepting any mission commands from this communication partner | MAV_MISSION_RESULT_ENUM_END = 15 // | )
MAV_MISSION_RESULT result in a mavlink mission ack
const ( MAV_SEVERITY_EMERGENCY = 0 // System is unusable. This is a "panic" condition. | MAV_SEVERITY_ALERT = 1 // Action should be taken immediately. Indicates error in non-critical systems. | MAV_SEVERITY_CRITICAL = 2 // Action must be taken immediately. Indicates failure in a primary system. | MAV_SEVERITY_ERROR = 3 // Indicates an error in secondary/redundant systems. | MAV_SEVERITY_WARNING = 4 // Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | MAV_SEVERITY_NOTICE = 5 // An unusual event has occurred, though not an error condition. This should be investigated for the root cause. | MAV_SEVERITY_INFO = 6 // Normal operational messages. Useful for logging. No action is required for these messages. | MAV_SEVERITY_DEBUG = 7 // Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | MAV_SEVERITY_ENUM_END = 8 // | )
MAV_SEVERITY Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/.
const ( MAV_POWER_STATUS_BRICK_VALID = 1 // main brick power supply valid | MAV_POWER_STATUS_SERVO_VALID = 2 // main servo power supply valid for FMU | MAV_POWER_STATUS_USB_CONNECTED = 4 // USB power is connected | MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 // peripheral supply is in over-current state | MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 // hi-power peripheral supply is in over-current state | MAV_POWER_STATUS_CHANGED = 32 // Power status has changed since boot | MAV_POWER_STATUS_ENUM_END = 33 // | )
MAV_POWER_STATUS Power supply status flags (bitmask)
const ( SERIAL_CONTROL_DEV_TELEM1 = 0 // First telemetry port | SERIAL_CONTROL_DEV_TELEM2 = 1 // Second telemetry port | SERIAL_CONTROL_DEV_GPS1 = 2 // First GPS port | SERIAL_CONTROL_DEV_GPS2 = 3 // Second GPS port | SERIAL_CONTROL_DEV_ENUM_END = 4 // | )
SERIAL_CONTROL_DEV SERIAL_CONTROL device types
const ( SERIAL_CONTROL_FLAG_REPLY = 1 // Set if this is a reply | SERIAL_CONTROL_FLAG_RESPOND = 2 // Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 // Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set | SERIAL_CONTROL_FLAG_BLOCKING = 8 // Block on writes to the serial port | SERIAL_CONTROL_FLAG_MULTI = 16 // Send multiple replies until port is drained | SERIAL_CONTROL_FLAG_ENUM_END = 17 // | )
SERIAL_CONTROL_FLAG SERIAL_CONTROL flags (bitmask)
const ( MAV_DISTANCE_SENSOR_LASER = 0 // Laser altimeter, e.g. LightWare SF02/F or PulsedLight units | MAV_DISTANCE_SENSOR_ULTRASOUND = 1 // Ultrasound altimeter, e.g. MaxBotix units | MAV_DISTANCE_SENSOR_ENUM_END = 2 // | )
MAV_DISTANCE_SENSOR Enumeration of distance sensor types
const ( MAVLINK_MSG_GPS_STATUS_FIELD_satellite_prn_LEN = 20 MAVLINK_MSG_GPS_STATUS_FIELD_satellite_used_LEN = 20 MAVLINK_MSG_GPS_STATUS_FIELD_satellite_elevation_LEN = 20 MAVLINK_MSG_GPS_STATUS_FIELD_satellite_azimuth_LEN = 20 MAVLINK_MSG_GPS_STATUS_FIELD_satellite_snr_LEN = 20 )
const ( MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_roll_LEN = 4 MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_pitch_LEN = 4 MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_yaw_LEN = 4 MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_thrust_LEN = 4 )
const ( MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_roll_LEN = 4 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_pitch_LEN = 4 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_yaw_LEN = 4 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_thrust_LEN = 4 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_led_red_LEN = 4 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_led_blue_LEN = 4 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_led_green_LEN = 4 )
const ( MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_left_LEN = 10 MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_right_LEN = 10 )
const ( MAVLINK_BIG_ENDIAN = 0 MAVLINK_LITTLE_ENDIAN = 1 MAVLINK_STX = 254 MAVLINK_ENDIAN = MAVLINK_LITTLE_ENDIAN MAVLINK_ALIGNED_FIELDS = 1 MAVLINK_CRC_EXTRA = 1 X25_INIT_CRC = 0xffff X25_VALIDATE_CRC = 0xf0b8 )
const ( MAVLINK_BUILD_DATE = "Fri Sep 26 19:23:02 2014" MAVLINK_WIRE_PROTOCOL_VERSION = "1.0" MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 255 MAVLINK_VERSION = 3 )
const (
MAVLINK_MSG_ATTITUDE_SETPOINT_EXTERNAL_FIELD_q_LEN = 4
)
const (
MAVLINK_MSG_AUTH_KEY_FIELD_key_LEN = 32
)
const (
MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_passkey_LEN = 25
)
const (
MAVLINK_MSG_DEBUG_VECT_FIELD_name_LEN = 10
)
const (
MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_data_LEN = 253
)
const (
MAVLINK_MSG_FILE_TRANSFER_DIR_LIST_FIELD_dir_path_LEN = 240
)
const (
MAVLINK_MSG_FILE_TRANSFER_START_FIELD_dest_path_LEN = 240
)
const (
MAVLINK_MSG_GPS_INJECT_DATA_FIELD_data_LEN = 110
)
const (
MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_attitude_quaternion_LEN = 4
)
const (
MAVLINK_MSG_LOG_DATA_FIELD_data_LEN = 90
)
const (
MAVLINK_MSG_MEMORY_VECT_FIELD_value_LEN = 32
)
const (
MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_name_LEN = 10
)
const (
MAVLINK_MSG_NAMED_VALUE_INT_FIELD_name_LEN = 10
)
const (
MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_param_id_LEN = 16
)
const (
MAVLINK_MSG_PARAM_SET_FIELD_param_id_LEN = 16
)
const (
MAVLINK_MSG_PARAM_VALUE_FIELD_param_id_LEN = 16
)
const (
MAVLINK_MSG_SERIAL_CONTROL_FIELD_data_LEN = 70
)
const (
MAVLINK_MSG_STATUSTEXT_FIELD_text_LEN = 50
)
const (
MAVLINK_MSG_TERRAIN_DATA_FIELD_data_LEN = 16
)
Variables ¶
This section is empty.
Functions ¶
This section is empty.
Types ¶
type Attitude ¶
type Attitude struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) ROLL float32 // Roll angle (rad, -pi..+pi) PITCH float32 // Pitch angle (rad, -pi..+pi) YAW float32 // Yaw angle (rad, -pi..+pi) ROLLSPEED float32 // Roll angular speed (rad/s) PITCHSPEED float32 // Pitch angular speed (rad/s) YAWSPEED float32 // Yaw angular speed (rad/s) }
MESSAGE ATTITUDE
MAVLINK_MSG_ID_ATTITUDE 30
MAVLINK_MSG_ID_ATTITUDE_LEN 28
MAVLINK_MSG_ID_ATTITUDE_CRC 39
func NewAttitude ¶
func NewAttitude(TIME_BOOT_MS uint32, ROLL float32, PITCH float32, YAW float32, ROLLSPEED float32, PITCHSPEED float32, YAWSPEED float32) *Attitude
NewAttitude returns a new Attitude
type AttitudeQuaternion ¶
type AttitudeQuaternion struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) Q1 float32 // Quaternion component 1, w (1 in null-rotation) Q2 float32 // Quaternion component 2, x (0 in null-rotation) Q3 float32 // Quaternion component 3, y (0 in null-rotation) Q4 float32 // Quaternion component 4, z (0 in null-rotation) ROLLSPEED float32 // Roll angular speed (rad/s) PITCHSPEED float32 // Pitch angular speed (rad/s) YAWSPEED float32 // Yaw angular speed (rad/s) }
MESSAGE ATTITUDE_QUATERNION
MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31
MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32
MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246
func NewAttitudeQuaternion ¶
func NewAttitudeQuaternion(TIME_BOOT_MS uint32, Q1 float32, Q2 float32, Q3 float32, Q4 float32, ROLLSPEED float32, PITCHSPEED float32, YAWSPEED float32) *AttitudeQuaternion
NewAttitudeQuaternion returns a new AttitudeQuaternion
func (*AttitudeQuaternion) Crc ¶
func (*AttitudeQuaternion) Crc() uint8
Crc returns the AttitudeQuaternion Message CRC
func (*AttitudeQuaternion) Decode ¶
func (m *AttitudeQuaternion) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the AttitudeQuaternion
func (*AttitudeQuaternion) Id ¶
func (*AttitudeQuaternion) Id() uint8
Id returns the AttitudeQuaternion Message ID
func (*AttitudeQuaternion) Len ¶
func (*AttitudeQuaternion) Len() uint8
Len returns the AttitudeQuaternion Message Length
func (*AttitudeQuaternion) Pack ¶
func (m *AttitudeQuaternion) Pack() []byte
Pack returns a packed byte array which represents a AttitudeQuaternion payload
type AttitudeSetpointExternal ¶
type AttitudeSetpointExternal struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot Q [4]float32 // Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) BODY_ROLL_RATE float32 // Body roll rate in radians per second BODY_PITCH_RATE float32 // Body roll rate in radians per second BODY_YAW_RATE float32 // Body roll rate in radians per second THRUST float32 // Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID TYPE_MASK uint8 // Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude }
MESSAGE ATTITUDE_SETPOINT_EXTERNAL
MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL 82
MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN 39
MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_CRC 147
func NewAttitudeSetpointExternal ¶
func NewAttitudeSetpointExternal(TIME_BOOT_MS uint32, Q [4]float32, BODY_ROLL_RATE float32, BODY_PITCH_RATE float32, BODY_YAW_RATE float32, THRUST float32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, TYPE_MASK uint8) *AttitudeSetpointExternal
NewAttitudeSetpointExternal returns a new AttitudeSetpointExternal
func (*AttitudeSetpointExternal) Crc ¶
func (*AttitudeSetpointExternal) Crc() uint8
Crc returns the AttitudeSetpointExternal Message CRC
func (*AttitudeSetpointExternal) Decode ¶
func (m *AttitudeSetpointExternal) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the AttitudeSetpointExternal
func (*AttitudeSetpointExternal) Id ¶
func (*AttitudeSetpointExternal) Id() uint8
Id returns the AttitudeSetpointExternal Message ID
func (*AttitudeSetpointExternal) Len ¶
func (*AttitudeSetpointExternal) Len() uint8
Len returns the AttitudeSetpointExternal Message Length
func (*AttitudeSetpointExternal) Pack ¶
func (m *AttitudeSetpointExternal) Pack() []byte
Pack returns a packed byte array which represents a AttitudeSetpointExternal payload
type AuthKey ¶
type AuthKey struct {
KEY [32]uint8 // key
}
MESSAGE AUTH_KEY
MAVLINK_MSG_ID_AUTH_KEY 7
MAVLINK_MSG_ID_AUTH_KEY_LEN 32
MAVLINK_MSG_ID_AUTH_KEY_CRC 119
type BatteryStatus ¶
type BatteryStatus struct { CURRENT_CONSUMED int32 // Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate ENERGY_CONSUMED int32 // Consumed energy, in 100*Joules (integrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate VOLTAGE_CELL_1 uint16 // Battery voltage of cell 1, in millivolts (1 = 1 millivolt) VOLTAGE_CELL_2 uint16 // Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell VOLTAGE_CELL_3 uint16 // Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell VOLTAGE_CELL_4 uint16 // Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell VOLTAGE_CELL_5 uint16 // Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell VOLTAGE_CELL_6 uint16 // Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell CURRENT_BATTERY int16 // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current ACCU_ID uint8 // Accupack ID BATTERY_REMAINING int8 // Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery }
MESSAGE BATTERY_STATUS
MAVLINK_MSG_ID_BATTERY_STATUS 147
MAVLINK_MSG_ID_BATTERY_STATUS_LEN 24
MAVLINK_MSG_ID_BATTERY_STATUS_CRC 177
func NewBatteryStatus ¶
func NewBatteryStatus(CURRENT_CONSUMED int32, ENERGY_CONSUMED int32, VOLTAGE_CELL_1 uint16, VOLTAGE_CELL_2 uint16, VOLTAGE_CELL_3 uint16, VOLTAGE_CELL_4 uint16, VOLTAGE_CELL_5 uint16, VOLTAGE_CELL_6 uint16, CURRENT_BATTERY int16, ACCU_ID uint8, BATTERY_REMAINING int8) *BatteryStatus
NewBatteryStatus returns a new BatteryStatus
func (*BatteryStatus) Crc ¶
func (*BatteryStatus) Crc() uint8
Crc returns the BatteryStatus Message CRC
func (*BatteryStatus) Decode ¶
func (m *BatteryStatus) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the BatteryStatus
func (*BatteryStatus) Len ¶
func (*BatteryStatus) Len() uint8
Len returns the BatteryStatus Message Length
func (*BatteryStatus) Pack ¶
func (m *BatteryStatus) Pack() []byte
Pack returns a packed byte array which represents a BatteryStatus payload
type ChangeOperatorControl ¶
type ChangeOperatorControl struct { TARGET_SYSTEM uint8 // System the GCS requests control for CONTROL_REQUEST uint8 // 0: request control of this MAV, 1: Release control of this MAV VERSION uint8 // 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. PASSKEY [25]uint8 // Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" }
MESSAGE CHANGE_OPERATOR_CONTROL
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC 217
func NewChangeOperatorControl ¶
func NewChangeOperatorControl(TARGET_SYSTEM uint8, CONTROL_REQUEST uint8, VERSION uint8, PASSKEY [25]uint8) *ChangeOperatorControl
NewChangeOperatorControl returns a new ChangeOperatorControl
func (*ChangeOperatorControl) Crc ¶
func (*ChangeOperatorControl) Crc() uint8
Crc returns the ChangeOperatorControl Message CRC
func (*ChangeOperatorControl) Decode ¶
func (m *ChangeOperatorControl) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the ChangeOperatorControl
func (*ChangeOperatorControl) Id ¶
func (*ChangeOperatorControl) Id() uint8
Id returns the ChangeOperatorControl Message ID
func (*ChangeOperatorControl) Len ¶
func (*ChangeOperatorControl) Len() uint8
Len returns the ChangeOperatorControl Message Length
func (*ChangeOperatorControl) Pack ¶
func (m *ChangeOperatorControl) Pack() []byte
Pack returns a packed byte array which represents a ChangeOperatorControl payload
type ChangeOperatorControlAck ¶
type ChangeOperatorControlAck struct { GCS_SYSTEM_ID uint8 // ID of the GCS this message CONTROL_REQUEST uint8 // 0: request control of this MAV, 1: Release control of this MAV ACK uint8 // 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control }
MESSAGE CHANGE_OPERATOR_CONTROL_ACK
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104
func NewChangeOperatorControlAck ¶
func NewChangeOperatorControlAck(GCS_SYSTEM_ID uint8, CONTROL_REQUEST uint8, ACK uint8) *ChangeOperatorControlAck
NewChangeOperatorControlAck returns a new ChangeOperatorControlAck
func (*ChangeOperatorControlAck) Crc ¶
func (*ChangeOperatorControlAck) Crc() uint8
Crc returns the ChangeOperatorControlAck Message CRC
func (*ChangeOperatorControlAck) Decode ¶
func (m *ChangeOperatorControlAck) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the ChangeOperatorControlAck
func (*ChangeOperatorControlAck) Id ¶
func (*ChangeOperatorControlAck) Id() uint8
Id returns the ChangeOperatorControlAck Message ID
func (*ChangeOperatorControlAck) Len ¶
func (*ChangeOperatorControlAck) Len() uint8
Len returns the ChangeOperatorControlAck Message Length
func (*ChangeOperatorControlAck) Pack ¶
func (m *ChangeOperatorControlAck) Pack() []byte
Pack returns a packed byte array which represents a ChangeOperatorControlAck payload
type CommandAck ¶
type CommandAck struct { COMMAND uint16 // Command ID, as defined by MAV_CMD enum. RESULT uint8 // See MAV_RESULT enum }
MESSAGE COMMAND_ACK
MAVLINK_MSG_ID_COMMAND_ACK 77
MAVLINK_MSG_ID_COMMAND_ACK_LEN 3
MAVLINK_MSG_ID_COMMAND_ACK_CRC 143
func NewCommandAck ¶
func NewCommandAck(COMMAND uint16, RESULT uint8) *CommandAck
NewCommandAck returns a new CommandAck
func (*CommandAck) Decode ¶
func (m *CommandAck) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the CommandAck
func (*CommandAck) Pack ¶
func (m *CommandAck) Pack() []byte
Pack returns a packed byte array which represents a CommandAck payload
type CommandLong ¶
type CommandLong struct { PARAM1 float32 // Parameter 1, as defined by MAV_CMD enum. PARAM2 float32 // Parameter 2, as defined by MAV_CMD enum. PARAM3 float32 // Parameter 3, as defined by MAV_CMD enum. PARAM4 float32 // Parameter 4, as defined by MAV_CMD enum. PARAM5 float32 // Parameter 5, as defined by MAV_CMD enum. PARAM6 float32 // Parameter 6, as defined by MAV_CMD enum. PARAM7 float32 // Parameter 7, as defined by MAV_CMD enum. COMMAND uint16 // Command ID, as defined by MAV_CMD enum. TARGET_SYSTEM uint8 // System which should execute the command TARGET_COMPONENT uint8 // Component which should execute the command, 0 for all components CONFIRMATION uint8 // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) }
MESSAGE COMMAND_LONG
MAVLINK_MSG_ID_COMMAND_LONG 76
MAVLINK_MSG_ID_COMMAND_LONG_LEN 33
MAVLINK_MSG_ID_COMMAND_LONG_CRC 152
func NewCommandLong ¶
func NewCommandLong(PARAM1 float32, PARAM2 float32, PARAM3 float32, PARAM4 float32, PARAM5 float32, PARAM6 float32, PARAM7 float32, COMMAND uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, CONFIRMATION uint8) *CommandLong
NewCommandLong returns a new CommandLong
func (*CommandLong) Decode ¶
func (m *CommandLong) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the CommandLong
func (*CommandLong) Len ¶
func (*CommandLong) Len() uint8
Len returns the CommandLong Message Length
func (*CommandLong) Pack ¶
func (m *CommandLong) Pack() []byte
Pack returns a packed byte array which represents a CommandLong payload
type DataStream ¶
type DataStream struct { MESSAGE_RATE uint16 // The requested interval between two messages of this type STREAM_ID uint8 // The ID of the requested data stream ON_OFF uint8 // 1 stream is enabled, 0 stream is stopped. }
MESSAGE DATA_STREAM
MAVLINK_MSG_ID_DATA_STREAM 67
MAVLINK_MSG_ID_DATA_STREAM_LEN 4
MAVLINK_MSG_ID_DATA_STREAM_CRC 21
func NewDataStream ¶
func NewDataStream(MESSAGE_RATE uint16, STREAM_ID uint8, ON_OFF uint8) *DataStream
NewDataStream returns a new DataStream
func (*DataStream) Decode ¶
func (m *DataStream) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the DataStream
func (*DataStream) Pack ¶
func (m *DataStream) Pack() []byte
Pack returns a packed byte array which represents a DataStream payload
type DataTransmissionHandshake ¶
type DataTransmissionHandshake struct { SIZE uint32 // total data size in bytes (set on ACK only) WIDTH uint16 // Width of a matrix or image HEIGHT uint16 // Height of a matrix or image PACKETS uint16 // number of packets being sent (set on ACK only) TYPE uint8 // type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) PAYLOAD uint8 // payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) JPG_QUALITY uint8 // JPEG quality out of [1,100] }
MESSAGE DATA_TRANSMISSION_HANDSHAKE
MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130
MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13
MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29
func NewDataTransmissionHandshake ¶
func NewDataTransmissionHandshake(SIZE uint32, WIDTH uint16, HEIGHT uint16, PACKETS uint16, TYPE uint8, PAYLOAD uint8, JPG_QUALITY uint8) *DataTransmissionHandshake
NewDataTransmissionHandshake returns a new DataTransmissionHandshake
func (*DataTransmissionHandshake) Crc ¶
func (*DataTransmissionHandshake) Crc() uint8
Crc returns the DataTransmissionHandshake Message CRC
func (*DataTransmissionHandshake) Decode ¶
func (m *DataTransmissionHandshake) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the DataTransmissionHandshake
func (*DataTransmissionHandshake) Id ¶
func (*DataTransmissionHandshake) Id() uint8
Id returns the DataTransmissionHandshake Message ID
func (*DataTransmissionHandshake) Len ¶
func (*DataTransmissionHandshake) Len() uint8
Len returns the DataTransmissionHandshake Message Length
func (*DataTransmissionHandshake) Pack ¶
func (m *DataTransmissionHandshake) Pack() []byte
Pack returns a packed byte array which represents a DataTransmissionHandshake payload
type Debug ¶
type Debug struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) VALUE float32 // DEBUG value IND uint8 // index of debug variable }
MESSAGE DEBUG
MAVLINK_MSG_ID_DEBUG 254
MAVLINK_MSG_ID_DEBUG_LEN 9
MAVLINK_MSG_ID_DEBUG_CRC 46
type DebugVect ¶
type DebugVect struct { TIME_USEC uint64 // Timestamp X float32 // x Y float32 // y Z float32 // z NAME [10]uint8 // Name }
MESSAGE DEBUG_VECT
MAVLINK_MSG_ID_DEBUG_VECT 250
MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
MAVLINK_MSG_ID_DEBUG_VECT_CRC 49
func NewDebugVect ¶
NewDebugVect returns a new DebugVect
type DistanceSensor ¶
type DistanceSensor struct { TIME_BOOT_MS uint32 // Time since system boot MIN_DISTANCE uint16 // Minimum distance the sensor can measure in centimeters MAX_DISTANCE uint16 // Maximum distance the sensor can measure in centimeters CURRENT_DISTANCE uint16 // Current distance reading TYPE uint8 // Type from MAV_DISTANCE_SENSOR enum. ID uint8 // Onboard ID of the sensor ORIENTATION uint8 // Direction the sensor faces from FIXME enum. COVARIANCE uint8 // Measurement covariance in centimeters, 0 for unknown / invalid readings }
MESSAGE DISTANCE_SENSOR
MAVLINK_MSG_ID_DISTANCE_SENSOR 132
MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14
MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85
func NewDistanceSensor ¶
func NewDistanceSensor(TIME_BOOT_MS uint32, MIN_DISTANCE uint16, MAX_DISTANCE uint16, CURRENT_DISTANCE uint16, TYPE uint8, ID uint8, ORIENTATION uint8, COVARIANCE uint8) *DistanceSensor
NewDistanceSensor returns a new DistanceSensor
func (*DistanceSensor) Crc ¶
func (*DistanceSensor) Crc() uint8
Crc returns the DistanceSensor Message CRC
func (*DistanceSensor) Decode ¶
func (m *DistanceSensor) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the DistanceSensor
func (*DistanceSensor) Id ¶
func (*DistanceSensor) Id() uint8
Id returns the DistanceSensor Message ID
func (*DistanceSensor) Len ¶
func (*DistanceSensor) Len() uint8
Len returns the DistanceSensor Message Length
func (*DistanceSensor) Pack ¶
func (m *DistanceSensor) Pack() []byte
Pack returns a packed byte array which represents a DistanceSensor payload
type EncapsulatedData ¶
type EncapsulatedData struct { SEQNR uint16 // sequence number (starting with 0 on every transmission) DATA [253]uint8 // image data bytes }
MESSAGE ENCAPSULATED_DATA
MAVLINK_MSG_ID_ENCAPSULATED_DATA 131
MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255
MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223
func NewEncapsulatedData ¶
func NewEncapsulatedData(SEQNR uint16, DATA [253]uint8) *EncapsulatedData
NewEncapsulatedData returns a new EncapsulatedData
func (*EncapsulatedData) Crc ¶
func (*EncapsulatedData) Crc() uint8
Crc returns the EncapsulatedData Message CRC
func (*EncapsulatedData) Decode ¶
func (m *EncapsulatedData) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the EncapsulatedData
func (*EncapsulatedData) Id ¶
func (*EncapsulatedData) Id() uint8
Id returns the EncapsulatedData Message ID
func (*EncapsulatedData) Len ¶
func (*EncapsulatedData) Len() uint8
Len returns the EncapsulatedData Message Length
func (*EncapsulatedData) Pack ¶
func (m *EncapsulatedData) Pack() []byte
Pack returns a packed byte array which represents a EncapsulatedData payload
type FileTransferDirList ¶
type FileTransferDirList struct { TRANSFER_UID uint64 // Unique transfer ID DIR_PATH [240]uint8 // Directory path to list FLAGS uint8 // RESERVED }
MESSAGE FILE_TRANSFER_DIR_LIST
MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST 111
MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN 249
MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC 93
func NewFileTransferDirList ¶
func NewFileTransferDirList(TRANSFER_UID uint64, DIR_PATH [240]uint8, FLAGS uint8) *FileTransferDirList
NewFileTransferDirList returns a new FileTransferDirList
func (*FileTransferDirList) Crc ¶
func (*FileTransferDirList) Crc() uint8
Crc returns the FileTransferDirList Message CRC
func (*FileTransferDirList) Decode ¶
func (m *FileTransferDirList) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the FileTransferDirList
func (*FileTransferDirList) Id ¶
func (*FileTransferDirList) Id() uint8
Id returns the FileTransferDirList Message ID
func (*FileTransferDirList) Len ¶
func (*FileTransferDirList) Len() uint8
Len returns the FileTransferDirList Message Length
func (*FileTransferDirList) Pack ¶
func (m *FileTransferDirList) Pack() []byte
Pack returns a packed byte array which represents a FileTransferDirList payload
type FileTransferRes ¶
type FileTransferRes struct { TRANSFER_UID uint64 // Unique transfer ID RESULT uint8 // 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device }
MESSAGE FILE_TRANSFER_RES
MAVLINK_MSG_ID_FILE_TRANSFER_RES 112
MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN 9
MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC 124
func NewFileTransferRes ¶
func NewFileTransferRes(TRANSFER_UID uint64, RESULT uint8) *FileTransferRes
NewFileTransferRes returns a new FileTransferRes
func (*FileTransferRes) Crc ¶
func (*FileTransferRes) Crc() uint8
Crc returns the FileTransferRes Message CRC
func (*FileTransferRes) Decode ¶
func (m *FileTransferRes) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the FileTransferRes
func (*FileTransferRes) Id ¶
func (*FileTransferRes) Id() uint8
Id returns the FileTransferRes Message ID
func (*FileTransferRes) Len ¶
func (*FileTransferRes) Len() uint8
Len returns the FileTransferRes Message Length
func (*FileTransferRes) Pack ¶
func (m *FileTransferRes) Pack() []byte
Pack returns a packed byte array which represents a FileTransferRes payload
type FileTransferStart ¶
type FileTransferStart struct { TRANSFER_UID uint64 // Unique transfer ID FILE_SIZE uint32 // File size in bytes DEST_PATH [240]uint8 // Destination path DIRECTION uint8 // Transfer direction: 0: from requester, 1: to requester FLAGS uint8 // RESERVED }
MESSAGE FILE_TRANSFER_START
MAVLINK_MSG_ID_FILE_TRANSFER_START 110
MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN 254
MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC 235
func NewFileTransferStart ¶
func NewFileTransferStart(TRANSFER_UID uint64, FILE_SIZE uint32, DEST_PATH [240]uint8, DIRECTION uint8, FLAGS uint8) *FileTransferStart
NewFileTransferStart returns a new FileTransferStart
func (*FileTransferStart) Crc ¶
func (*FileTransferStart) Crc() uint8
Crc returns the FileTransferStart Message CRC
func (*FileTransferStart) Decode ¶
func (m *FileTransferStart) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the FileTransferStart
func (*FileTransferStart) Id ¶
func (*FileTransferStart) Id() uint8
Id returns the FileTransferStart Message ID
func (*FileTransferStart) Len ¶
func (*FileTransferStart) Len() uint8
Len returns the FileTransferStart Message Length
func (*FileTransferStart) Pack ¶
func (m *FileTransferStart) Pack() []byte
Pack returns a packed byte array which represents a FileTransferStart payload
type GlobalPositionInt ¶
type GlobalPositionInt struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) LAT int32 // Latitude, expressed as * 1E7 LON int32 // Longitude, expressed as * 1E7 ALT int32 // Altitude in meters, expressed as * 1000 (millimeters), above MSL RELATIVE_ALT int32 // Altitude above ground in meters, expressed as * 1000 (millimeters) VX int16 // Ground X Speed (Latitude), expressed as m/s * 100 VY int16 // Ground Y Speed (Longitude), expressed as m/s * 100 VZ int16 // Ground Z Speed (Altitude), expressed as m/s * 100 HDG uint16 // Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX }
MESSAGE GLOBAL_POSITION_INT
MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33
MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28
MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104
func NewGlobalPositionInt ¶
func NewGlobalPositionInt(TIME_BOOT_MS uint32, LAT int32, LON int32, ALT int32, RELATIVE_ALT int32, VX int16, VY int16, VZ int16, HDG uint16) *GlobalPositionInt
NewGlobalPositionInt returns a new GlobalPositionInt
func (*GlobalPositionInt) Crc ¶
func (*GlobalPositionInt) Crc() uint8
Crc returns the GlobalPositionInt Message CRC
func (*GlobalPositionInt) Decode ¶
func (m *GlobalPositionInt) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the GlobalPositionInt
func (*GlobalPositionInt) Id ¶
func (*GlobalPositionInt) Id() uint8
Id returns the GlobalPositionInt Message ID
func (*GlobalPositionInt) Len ¶
func (*GlobalPositionInt) Len() uint8
Len returns the GlobalPositionInt Message Length
func (*GlobalPositionInt) Pack ¶
func (m *GlobalPositionInt) Pack() []byte
Pack returns a packed byte array which represents a GlobalPositionInt payload
type GlobalPositionSetpointExternalInt ¶
type GlobalPositionSetpointExternalInt struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. LAT_INT int32 // X Position in WGS84 frame in 1e7 * meters LON_INT int32 // Y Position in WGS84 frame in 1e7 * meters ALT float32 // Altitude in WGS84, not AMSL VX float32 // X velocity in NED frame in meter / s VY float32 // Y velocity in NED frame in meter / s VZ float32 // Z velocity in NED frame in meter / s AFX float32 // X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N AFY float32 // Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N AFZ float32 // Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N TYPE_MASK uint16 // 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 TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE GLOBAL_POSITION_SETPOINT_EXTERNAL_INT
MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT 84
MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN 44
MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC 198
func NewGlobalPositionSetpointExternalInt ¶
func NewGlobalPositionSetpointExternalInt(TIME_BOOT_MS uint32, LAT_INT int32, LON_INT int32, ALT float32, VX float32, VY float32, VZ float32, AFX float32, AFY float32, AFZ float32, TYPE_MASK uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *GlobalPositionSetpointExternalInt
NewGlobalPositionSetpointExternalInt returns a new GlobalPositionSetpointExternalInt
func (*GlobalPositionSetpointExternalInt) Crc ¶
func (*GlobalPositionSetpointExternalInt) Crc() uint8
Crc returns the GlobalPositionSetpointExternalInt Message CRC
func (*GlobalPositionSetpointExternalInt) Decode ¶
func (m *GlobalPositionSetpointExternalInt) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the GlobalPositionSetpointExternalInt
func (*GlobalPositionSetpointExternalInt) Id ¶
func (*GlobalPositionSetpointExternalInt) Id() uint8
Id returns the GlobalPositionSetpointExternalInt Message ID
func (*GlobalPositionSetpointExternalInt) Len ¶
func (*GlobalPositionSetpointExternalInt) Len() uint8
Len returns the GlobalPositionSetpointExternalInt Message Length
func (*GlobalPositionSetpointExternalInt) Pack ¶
func (m *GlobalPositionSetpointExternalInt) Pack() []byte
Pack returns a packed byte array which represents a GlobalPositionSetpointExternalInt payload
type GlobalPositionSetpointInt ¶
type GlobalPositionSetpointInt struct { LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 LONGITUDE int32 // Longitude (WGS84), in degrees * 1E7 ALTITUDE int32 // Altitude (WGS84), in meters * 1000 (positive for up) YAW int16 // Desired yaw angle in degrees * 100 COORDINATE_FRAME uint8 // Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT }
MESSAGE GLOBAL_POSITION_SETPOINT_INT
MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT 52
MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 15
MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC 141
func NewGlobalPositionSetpointInt ¶
func NewGlobalPositionSetpointInt(LATITUDE int32, LONGITUDE int32, ALTITUDE int32, YAW int16, COORDINATE_FRAME uint8) *GlobalPositionSetpointInt
NewGlobalPositionSetpointInt returns a new GlobalPositionSetpointInt
func (*GlobalPositionSetpointInt) Crc ¶
func (*GlobalPositionSetpointInt) Crc() uint8
Crc returns the GlobalPositionSetpointInt Message CRC
func (*GlobalPositionSetpointInt) Decode ¶
func (m *GlobalPositionSetpointInt) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the GlobalPositionSetpointInt
func (*GlobalPositionSetpointInt) Id ¶
func (*GlobalPositionSetpointInt) Id() uint8
Id returns the GlobalPositionSetpointInt Message ID
func (*GlobalPositionSetpointInt) Len ¶
func (*GlobalPositionSetpointInt) Len() uint8
Len returns the GlobalPositionSetpointInt Message Length
func (*GlobalPositionSetpointInt) Pack ¶
func (m *GlobalPositionSetpointInt) Pack() []byte
Pack returns a packed byte array which represents a GlobalPositionSetpointInt payload
type GlobalVisionPositionEstimate ¶
type GlobalVisionPositionEstimate struct { USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) X float32 // Global X position Y float32 // Global Y position Z float32 // Global Z position ROLL float32 // Roll angle in rad PITCH float32 // Pitch angle in rad YAW float32 // Yaw angle in rad }
MESSAGE GLOBAL_VISION_POSITION_ESTIMATE
MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101
MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32
MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102
func NewGlobalVisionPositionEstimate ¶
func NewGlobalVisionPositionEstimate(USEC uint64, X float32, Y float32, Z float32, ROLL float32, PITCH float32, YAW float32) *GlobalVisionPositionEstimate
NewGlobalVisionPositionEstimate returns a new GlobalVisionPositionEstimate
func (*GlobalVisionPositionEstimate) Crc ¶
func (*GlobalVisionPositionEstimate) Crc() uint8
Crc returns the GlobalVisionPositionEstimate Message CRC
func (*GlobalVisionPositionEstimate) Decode ¶
func (m *GlobalVisionPositionEstimate) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the GlobalVisionPositionEstimate
func (*GlobalVisionPositionEstimate) Id ¶
func (*GlobalVisionPositionEstimate) Id() uint8
Id returns the GlobalVisionPositionEstimate Message ID
func (*GlobalVisionPositionEstimate) Len ¶
func (*GlobalVisionPositionEstimate) Len() uint8
Len returns the GlobalVisionPositionEstimate Message Length
func (*GlobalVisionPositionEstimate) Pack ¶
func (m *GlobalVisionPositionEstimate) Pack() []byte
Pack returns a packed byte array which represents a GlobalVisionPositionEstimate payload
type Gps2Raw ¶
type Gps2Raw struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) LAT int32 // Latitude (WGS84), in degrees * 1E7 LON int32 // Longitude (WGS84), in degrees * 1E7 ALT int32 // Altitude (WGS84), in meters * 1000 (positive for up) DGPS_AGE uint32 // Age of DGPS info EPH uint16 // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX EPV uint16 // GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX VEL uint16 // GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX COG uint16 // 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 uint8 // 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. SATELLITES_VISIBLE uint8 // Number of satellites visible. If unknown, set to 255 DGPS_NUMCH uint8 // Number of DGPS satellites }
MESSAGE GPS2_RAW
MAVLINK_MSG_ID_GPS2_RAW 124
MAVLINK_MSG_ID_GPS2_RAW_LEN 35
MAVLINK_MSG_ID_GPS2_RAW_CRC 87
func NewGps2Raw ¶
func NewGps2Raw(TIME_USEC uint64, LAT int32, LON int32, ALT int32, DGPS_AGE uint32, EPH uint16, EPV uint16, VEL uint16, COG uint16, FIX_TYPE uint8, SATELLITES_VISIBLE uint8, DGPS_NUMCH uint8) *Gps2Raw
NewGps2Raw returns a new Gps2Raw
type Gps2Rtk ¶
type Gps2Rtk struct { TIME_LAST_BASELINE_MS uint32 // Time since boot of last baseline message received in ms. TOW uint32 // GPS Time of Week of last baseline BASELINE_A_MM int32 // Current baseline in ECEF x or NED north component in mm. BASELINE_B_MM int32 // Current baseline in ECEF y or NED east component in mm. BASELINE_C_MM int32 // Current baseline in ECEF z or NED down component in mm. ACCURACY uint32 // Current estimate of baseline accuracy. IAR_NUM_HYPOTHESES int32 // Current number of integer ambiguity hypotheses. WN uint16 // GPS Week Number of last baseline RTK_RECEIVER_ID uint8 // Identification of connected RTK receiver. RTK_HEALTH uint8 // GPS-specific health report for RTK data. RTK_RATE uint8 // Rate of baseline messages being received by GPS, in HZ NSATS uint8 // Current number of sats used for RTK calculation. BASELINE_COORDS_TYPE uint8 // Coordinate system of baseline. 0 == ECEF, 1 == NED }
MESSAGE GPS2_RTK
MAVLINK_MSG_ID_GPS2_RTK 128
MAVLINK_MSG_ID_GPS2_RTK_LEN 35
MAVLINK_MSG_ID_GPS2_RTK_CRC 226
func NewGps2Rtk ¶
func NewGps2Rtk(TIME_LAST_BASELINE_MS uint32, TOW uint32, BASELINE_A_MM int32, BASELINE_B_MM int32, BASELINE_C_MM int32, ACCURACY uint32, IAR_NUM_HYPOTHESES int32, WN uint16, RTK_RECEIVER_ID uint8, RTK_HEALTH uint8, RTK_RATE uint8, NSATS uint8, BASELINE_COORDS_TYPE uint8) *Gps2Rtk
NewGps2Rtk returns a new Gps2Rtk
type GpsGlobalOrigin ¶
type GpsGlobalOrigin struct { LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 LONGITUDE int32 // Longitude (WGS84), in degrees * 1E7 ALTITUDE int32 // Altitude (WGS84), in meters * 1000 (positive for up) }
MESSAGE GPS_GLOBAL_ORIGIN
MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49
MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12
MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39
func NewGpsGlobalOrigin ¶
func NewGpsGlobalOrigin(LATITUDE int32, LONGITUDE int32, ALTITUDE int32) *GpsGlobalOrigin
NewGpsGlobalOrigin returns a new GpsGlobalOrigin
func (*GpsGlobalOrigin) Crc ¶
func (*GpsGlobalOrigin) Crc() uint8
Crc returns the GpsGlobalOrigin Message CRC
func (*GpsGlobalOrigin) Decode ¶
func (m *GpsGlobalOrigin) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the GpsGlobalOrigin
func (*GpsGlobalOrigin) Id ¶
func (*GpsGlobalOrigin) Id() uint8
Id returns the GpsGlobalOrigin Message ID
func (*GpsGlobalOrigin) Len ¶
func (*GpsGlobalOrigin) Len() uint8
Len returns the GpsGlobalOrigin Message Length
func (*GpsGlobalOrigin) Pack ¶
func (m *GpsGlobalOrigin) Pack() []byte
Pack returns a packed byte array which represents a GpsGlobalOrigin payload
type GpsInjectData ¶
type GpsInjectData struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID LEN uint8 // data length DATA [110]uint8 // raw data (110 is enough for 12 satellites of RTCMv2) }
MESSAGE GPS_INJECT_DATA
MAVLINK_MSG_ID_GPS_INJECT_DATA 123
MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113
MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250
func NewGpsInjectData ¶
func NewGpsInjectData(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, LEN uint8, DATA [110]uint8) *GpsInjectData
NewGpsInjectData returns a new GpsInjectData
func (*GpsInjectData) Crc ¶
func (*GpsInjectData) Crc() uint8
Crc returns the GpsInjectData Message CRC
func (*GpsInjectData) Decode ¶
func (m *GpsInjectData) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the GpsInjectData
func (*GpsInjectData) Len ¶
func (*GpsInjectData) Len() uint8
Len returns the GpsInjectData Message Length
func (*GpsInjectData) Pack ¶
func (m *GpsInjectData) Pack() []byte
Pack returns a packed byte array which represents a GpsInjectData payload
type GpsRawInt ¶
type GpsRawInt struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) LAT int32 // Latitude (WGS84), in degrees * 1E7 LON int32 // Longitude (WGS84), in degrees * 1E7 ALT int32 // Altitude (WGS84), in meters * 1000 (positive for up) EPH uint16 // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX EPV uint16 // GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX VEL uint16 // GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX COG uint16 // 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 uint8 // 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. SATELLITES_VISIBLE uint8 // Number of satellites visible. If unknown, set to 255 }
MESSAGE GPS_RAW_INT
MAVLINK_MSG_ID_GPS_RAW_INT 24
MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24
func NewGpsRawInt ¶
func NewGpsRawInt(TIME_USEC uint64, LAT int32, LON int32, ALT int32, EPH uint16, EPV uint16, VEL uint16, COG uint16, FIX_TYPE uint8, SATELLITES_VISIBLE uint8) *GpsRawInt
NewGpsRawInt returns a new GpsRawInt
type GpsRtk ¶
type GpsRtk struct { TIME_LAST_BASELINE_MS uint32 // Time since boot of last baseline message received in ms. TOW uint32 // GPS Time of Week of last baseline BASELINE_A_MM int32 // Current baseline in ECEF x or NED north component in mm. BASELINE_B_MM int32 // Current baseline in ECEF y or NED east component in mm. BASELINE_C_MM int32 // Current baseline in ECEF z or NED down component in mm. ACCURACY uint32 // Current estimate of baseline accuracy. IAR_NUM_HYPOTHESES int32 // Current number of integer ambiguity hypotheses. WN uint16 // GPS Week Number of last baseline RTK_RECEIVER_ID uint8 // Identification of connected RTK receiver. RTK_HEALTH uint8 // GPS-specific health report for RTK data. RTK_RATE uint8 // Rate of baseline messages being received by GPS, in HZ NSATS uint8 // Current number of sats used for RTK calculation. BASELINE_COORDS_TYPE uint8 // Coordinate system of baseline. 0 == ECEF, 1 == NED }
MESSAGE GPS_RTK
MAVLINK_MSG_ID_GPS_RTK 127
MAVLINK_MSG_ID_GPS_RTK_LEN 35
MAVLINK_MSG_ID_GPS_RTK_CRC 25
func NewGpsRtk ¶
func NewGpsRtk(TIME_LAST_BASELINE_MS uint32, TOW uint32, BASELINE_A_MM int32, BASELINE_B_MM int32, BASELINE_C_MM int32, ACCURACY uint32, IAR_NUM_HYPOTHESES int32, WN uint16, RTK_RECEIVER_ID uint8, RTK_HEALTH uint8, RTK_RATE uint8, NSATS uint8, BASELINE_COORDS_TYPE uint8) *GpsRtk
NewGpsRtk returns a new GpsRtk
type GpsStatus ¶
type GpsStatus struct { SATELLITES_VISIBLE uint8 // Number of satellites visible SATELLITE_PRN [20]uint8 // Global satellite ID SATELLITE_USED [20]uint8 // 0: Satellite not used, 1: used for localization SATELLITE_ELEVATION [20]uint8 // Elevation (0: right on top of receiver, 90: on the horizon) of satellite SATELLITE_AZIMUTH [20]uint8 // Direction of satellite, 0: 0 deg, 255: 360 deg. SATELLITE_SNR [20]uint8 // Signal to noise ratio of satellite }
MESSAGE GPS_STATUS
MAVLINK_MSG_ID_GPS_STATUS 25
MAVLINK_MSG_ID_GPS_STATUS_LEN 101
MAVLINK_MSG_ID_GPS_STATUS_CRC 23
func NewGpsStatus ¶
func NewGpsStatus(SATELLITES_VISIBLE uint8, SATELLITE_PRN [20]uint8, SATELLITE_USED [20]uint8, SATELLITE_ELEVATION [20]uint8, SATELLITE_AZIMUTH [20]uint8, SATELLITE_SNR [20]uint8) *GpsStatus
NewGpsStatus returns a new GpsStatus
type Heartbeat ¶
type Heartbeat struct { CUSTOM_MODE uint32 // A bitfield for use for autopilot-specific flags. TYPE uint8 // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) AUTOPILOT uint8 // Autopilot type / class. defined in MAV_AUTOPILOT ENUM BASE_MODE uint8 // System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h SYSTEM_STATUS uint8 // System status flag, see MAV_STATE ENUM MAVLINK_VERSION uint8 // MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version }
MESSAGE HEARTBEAT
MAVLINK_MSG_ID_HEARTBEAT 0
MAVLINK_MSG_ID_HEARTBEAT_LEN 9
MAVLINK_MSG_ID_HEARTBEAT_CRC 50
func NewHeartbeat ¶
func NewHeartbeat(CUSTOM_MODE uint32, TYPE uint8, AUTOPILOT uint8, BASE_MODE uint8, SYSTEM_STATUS uint8, MAVLINK_VERSION uint8) *Heartbeat
NewHeartbeat returns a new Heartbeat
type HighresImu ¶
type HighresImu struct { TIME_USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) XACC float32 // X acceleration (m/s^2) YACC float32 // Y acceleration (m/s^2) ZACC float32 // Z acceleration (m/s^2) XGYRO float32 // Angular speed around X axis (rad / sec) YGYRO float32 // Angular speed around Y axis (rad / sec) ZGYRO float32 // Angular speed around Z axis (rad / sec) XMAG float32 // X Magnetic field (Gauss) YMAG float32 // Y Magnetic field (Gauss) ZMAG float32 // Z Magnetic field (Gauss) ABS_PRESSURE float32 // Absolute pressure in millibar DIFF_PRESSURE float32 // Differential pressure in millibar PRESSURE_ALT float32 // Altitude calculated from pressure TEMPERATURE float32 // Temperature in degrees celsius FIELDS_UPDATED uint16 // Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature }
MESSAGE HIGHRES_IMU
MAVLINK_MSG_ID_HIGHRES_IMU 105
MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62
MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93
func NewHighresImu ¶
func NewHighresImu(TIME_USEC uint64, XACC float32, YACC float32, ZACC float32, XGYRO float32, YGYRO float32, ZGYRO float32, XMAG float32, YMAG float32, ZMAG float32, ABS_PRESSURE float32, DIFF_PRESSURE float32, PRESSURE_ALT float32, TEMPERATURE float32, FIELDS_UPDATED uint16) *HighresImu
NewHighresImu returns a new HighresImu
func (*HighresImu) Decode ¶
func (m *HighresImu) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the HighresImu
func (*HighresImu) Pack ¶
func (m *HighresImu) Pack() []byte
Pack returns a packed byte array which represents a HighresImu payload
type HilControls ¶
type HilControls struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) ROLL_AILERONS float32 // Control output -1 .. 1 PITCH_ELEVATOR float32 // Control output -1 .. 1 YAW_RUDDER float32 // Control output -1 .. 1 THROTTLE float32 // Throttle 0 .. 1 AUX1 float32 // Aux 1, -1 .. 1 AUX2 float32 // Aux 2, -1 .. 1 AUX3 float32 // Aux 3, -1 .. 1 AUX4 float32 // Aux 4, -1 .. 1 MODE uint8 // System mode (MAV_MODE) NAV_MODE uint8 // Navigation mode (MAV_NAV_MODE) }
MESSAGE HIL_CONTROLS
MAVLINK_MSG_ID_HIL_CONTROLS 91
MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42
MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63
func NewHilControls ¶
func NewHilControls(TIME_USEC uint64, ROLL_AILERONS float32, PITCH_ELEVATOR float32, YAW_RUDDER float32, THROTTLE float32, AUX1 float32, AUX2 float32, AUX3 float32, AUX4 float32, MODE uint8, NAV_MODE uint8) *HilControls
NewHilControls returns a new HilControls
func (*HilControls) Decode ¶
func (m *HilControls) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the HilControls
func (*HilControls) Len ¶
func (*HilControls) Len() uint8
Len returns the HilControls Message Length
func (*HilControls) Pack ¶
func (m *HilControls) Pack() []byte
Pack returns a packed byte array which represents a HilControls payload
type HilGps ¶
type HilGps struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) LAT int32 // Latitude (WGS84), in degrees * 1E7 LON int32 // Longitude (WGS84), in degrees * 1E7 ALT int32 // Altitude (WGS84), in meters * 1000 (positive for up) EPH uint16 // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 EPV uint16 // GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 VEL uint16 // GPS ground speed (m/s * 100). If unknown, set to: 65535 VN int16 // GPS velocity in cm/s in NORTH direction in earth-fixed NED frame VE int16 // GPS velocity in cm/s in EAST direction in earth-fixed NED frame VD int16 // GPS velocity in cm/s in DOWN direction in earth-fixed NED frame COG uint16 // Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 FIX_TYPE uint8 // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. SATELLITES_VISIBLE uint8 // Number of satellites visible. If unknown, set to 255 }
MESSAGE HIL_GPS
MAVLINK_MSG_ID_HIL_GPS 113
MAVLINK_MSG_ID_HIL_GPS_LEN 36
MAVLINK_MSG_ID_HIL_GPS_CRC 124
func NewHilGps ¶
func NewHilGps(TIME_USEC uint64, LAT int32, LON int32, ALT int32, EPH uint16, EPV uint16, VEL uint16, VN int16, VE int16, VD int16, COG uint16, FIX_TYPE uint8, SATELLITES_VISIBLE uint8) *HilGps
NewHilGps returns a new HilGps
type HilOpticalFlow ¶
type HilOpticalFlow struct { TIME_USEC uint64 // Timestamp (UNIX) FLOW_COMP_M_X float32 // Flow in meters in x-sensor direction, angular-speed compensated FLOW_COMP_M_Y float32 // Flow in meters in y-sensor direction, angular-speed compensated GROUND_DISTANCE float32 // Ground distance in meters. Positive value: distance known. Negative value: Unknown distance FLOW_X int16 // Flow in pixels in x-sensor direction FLOW_Y int16 // Flow in pixels in y-sensor direction SENSOR_ID uint8 // Sensor ID QUALITY uint8 // Optical flow quality / confidence. 0: bad, 255: maximum quality }
MESSAGE HIL_OPTICAL_FLOW
MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114
MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 26
MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 119
func NewHilOpticalFlow ¶
func NewHilOpticalFlow(TIME_USEC uint64, FLOW_COMP_M_X float32, FLOW_COMP_M_Y float32, GROUND_DISTANCE float32, FLOW_X int16, FLOW_Y int16, SENSOR_ID uint8, QUALITY uint8) *HilOpticalFlow
NewHilOpticalFlow returns a new HilOpticalFlow
func (*HilOpticalFlow) Crc ¶
func (*HilOpticalFlow) Crc() uint8
Crc returns the HilOpticalFlow Message CRC
func (*HilOpticalFlow) Decode ¶
func (m *HilOpticalFlow) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the HilOpticalFlow
func (*HilOpticalFlow) Id ¶
func (*HilOpticalFlow) Id() uint8
Id returns the HilOpticalFlow Message ID
func (*HilOpticalFlow) Len ¶
func (*HilOpticalFlow) Len() uint8
Len returns the HilOpticalFlow Message Length
func (*HilOpticalFlow) Pack ¶
func (m *HilOpticalFlow) Pack() []byte
Pack returns a packed byte array which represents a HilOpticalFlow payload
type HilRcInputsRaw ¶
type HilRcInputsRaw struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) CHAN1_RAW uint16 // RC channel 1 value, in microseconds CHAN2_RAW uint16 // RC channel 2 value, in microseconds CHAN3_RAW uint16 // RC channel 3 value, in microseconds CHAN4_RAW uint16 // RC channel 4 value, in microseconds CHAN5_RAW uint16 // RC channel 5 value, in microseconds CHAN6_RAW uint16 // RC channel 6 value, in microseconds CHAN7_RAW uint16 // RC channel 7 value, in microseconds CHAN8_RAW uint16 // RC channel 8 value, in microseconds CHAN9_RAW uint16 // RC channel 9 value, in microseconds CHAN10_RAW uint16 // RC channel 10 value, in microseconds CHAN11_RAW uint16 // RC channel 11 value, in microseconds CHAN12_RAW uint16 // RC channel 12 value, in microseconds RSSI uint8 // Receive signal strength indicator, 0: 0%, 255: 100% }
MESSAGE HIL_RC_INPUTS_RAW
MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92
MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33
MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC 54
func NewHilRcInputsRaw ¶
func NewHilRcInputsRaw(TIME_USEC uint64, CHAN1_RAW uint16, CHAN2_RAW uint16, CHAN3_RAW uint16, CHAN4_RAW uint16, CHAN5_RAW uint16, CHAN6_RAW uint16, CHAN7_RAW uint16, CHAN8_RAW uint16, CHAN9_RAW uint16, CHAN10_RAW uint16, CHAN11_RAW uint16, CHAN12_RAW uint16, RSSI uint8) *HilRcInputsRaw
NewHilRcInputsRaw returns a new HilRcInputsRaw
func (*HilRcInputsRaw) Crc ¶
func (*HilRcInputsRaw) Crc() uint8
Crc returns the HilRcInputsRaw Message CRC
func (*HilRcInputsRaw) Decode ¶
func (m *HilRcInputsRaw) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the HilRcInputsRaw
func (*HilRcInputsRaw) Id ¶
func (*HilRcInputsRaw) Id() uint8
Id returns the HilRcInputsRaw Message ID
func (*HilRcInputsRaw) Len ¶
func (*HilRcInputsRaw) Len() uint8
Len returns the HilRcInputsRaw Message Length
func (*HilRcInputsRaw) Pack ¶
func (m *HilRcInputsRaw) Pack() []byte
Pack returns a packed byte array which represents a HilRcInputsRaw payload
type HilSensor ¶
type HilSensor struct { TIME_USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) XACC float32 // X acceleration (m/s^2) YACC float32 // Y acceleration (m/s^2) ZACC float32 // Z acceleration (m/s^2) XGYRO float32 // Angular speed around X axis in body frame (rad / sec) YGYRO float32 // Angular speed around Y axis in body frame (rad / sec) ZGYRO float32 // Angular speed around Z axis in body frame (rad / sec) XMAG float32 // X Magnetic field (Gauss) YMAG float32 // Y Magnetic field (Gauss) ZMAG float32 // Z Magnetic field (Gauss) ABS_PRESSURE float32 // Absolute pressure in millibar DIFF_PRESSURE float32 // Differential pressure (airspeed) in millibar PRESSURE_ALT float32 // Altitude calculated from pressure TEMPERATURE float32 // Temperature in degrees celsius FIELDS_UPDATED uint32 // Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature }
MESSAGE HIL_SENSOR
MAVLINK_MSG_ID_HIL_SENSOR 107
MAVLINK_MSG_ID_HIL_SENSOR_LEN 64
MAVLINK_MSG_ID_HIL_SENSOR_CRC 108
func NewHilSensor ¶
func NewHilSensor(TIME_USEC uint64, XACC float32, YACC float32, ZACC float32, XGYRO float32, YGYRO float32, ZGYRO float32, XMAG float32, YMAG float32, ZMAG float32, ABS_PRESSURE float32, DIFF_PRESSURE float32, PRESSURE_ALT float32, TEMPERATURE float32, FIELDS_UPDATED uint32) *HilSensor
NewHilSensor returns a new HilSensor
type HilState ¶
type HilState struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) ROLL float32 // Roll angle (rad) PITCH float32 // Pitch angle (rad) YAW float32 // Yaw angle (rad) ROLLSPEED float32 // Body frame roll / phi angular speed (rad/s) PITCHSPEED float32 // Body frame pitch / theta angular speed (rad/s) YAWSPEED float32 // Body frame yaw / psi angular speed (rad/s) LAT int32 // Latitude, expressed as * 1E7 LON int32 // Longitude, expressed as * 1E7 ALT int32 // Altitude in meters, expressed as * 1000 (millimeters) VX int16 // Ground X Speed (Latitude), expressed as m/s * 100 VY int16 // Ground Y Speed (Longitude), expressed as m/s * 100 VZ int16 // Ground Z Speed (Altitude), expressed as m/s * 100 XACC int16 // X acceleration (mg) YACC int16 // Y acceleration (mg) ZACC int16 // Z acceleration (mg) }
MESSAGE HIL_STATE
MAVLINK_MSG_ID_HIL_STATE 90
MAVLINK_MSG_ID_HIL_STATE_LEN 56
MAVLINK_MSG_ID_HIL_STATE_CRC 183
func NewHilState ¶
func NewHilState(TIME_USEC uint64, ROLL float32, PITCH float32, YAW float32, ROLLSPEED float32, PITCHSPEED float32, YAWSPEED float32, LAT int32, LON int32, ALT int32, VX int16, VY int16, VZ int16, XACC int16, YACC int16, ZACC int16) *HilState
NewHilState returns a new HilState
type HilStateQuaternion ¶
type HilStateQuaternion struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) ATTITUDE_QUATERNION [4]float32 // Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) ROLLSPEED float32 // Body frame roll / phi angular speed (rad/s) PITCHSPEED float32 // Body frame pitch / theta angular speed (rad/s) YAWSPEED float32 // Body frame yaw / psi angular speed (rad/s) LAT int32 // Latitude, expressed as * 1E7 LON int32 // Longitude, expressed as * 1E7 ALT int32 // Altitude in meters, expressed as * 1000 (millimeters) VX int16 // Ground X Speed (Latitude), expressed as m/s * 100 VY int16 // Ground Y Speed (Longitude), expressed as m/s * 100 VZ int16 // Ground Z Speed (Altitude), expressed as m/s * 100 IND_AIRSPEED uint16 // Indicated airspeed, expressed as m/s * 100 TRUE_AIRSPEED uint16 // True airspeed, expressed as m/s * 100 XACC int16 // X acceleration (mg) YACC int16 // Y acceleration (mg) ZACC int16 // Z acceleration (mg) }
MESSAGE HIL_STATE_QUATERNION
MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115
MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64
MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4
func NewHilStateQuaternion ¶
func NewHilStateQuaternion(TIME_USEC uint64, ATTITUDE_QUATERNION [4]float32, ROLLSPEED float32, PITCHSPEED float32, YAWSPEED float32, LAT int32, LON int32, ALT int32, VX int16, VY int16, VZ int16, IND_AIRSPEED uint16, TRUE_AIRSPEED uint16, XACC int16, YACC int16, ZACC int16) *HilStateQuaternion
NewHilStateQuaternion returns a new HilStateQuaternion
func (*HilStateQuaternion) Crc ¶
func (*HilStateQuaternion) Crc() uint8
Crc returns the HilStateQuaternion Message CRC
func (*HilStateQuaternion) Decode ¶
func (m *HilStateQuaternion) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the HilStateQuaternion
func (*HilStateQuaternion) Id ¶
func (*HilStateQuaternion) Id() uint8
Id returns the HilStateQuaternion Message ID
func (*HilStateQuaternion) Len ¶
func (*HilStateQuaternion) Len() uint8
Len returns the HilStateQuaternion Message Length
func (*HilStateQuaternion) Pack ¶
func (m *HilStateQuaternion) Pack() []byte
Pack returns a packed byte array which represents a HilStateQuaternion payload
type LocalNedPositionSetpointExternal ¶
type LocalNedPositionSetpointExternal struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot X float32 // X Position in NED frame in meters Y float32 // Y Position in NED frame in meters Z float32 // Z Position in NED frame in meters (note, altitude is negative in NED) VX float32 // X velocity in NED frame in meter / s VY float32 // Y velocity in NED frame in meter / s VZ float32 // Z velocity in NED frame in meter / s AFX float32 // X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N AFY float32 // Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N AFZ float32 // Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N TYPE_MASK uint16 // 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 TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID COORDINATE_FRAME uint8 // Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7 }
MESSAGE LOCAL_NED_POSITION_SETPOINT_EXTERNAL
MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL 83
MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN 45
MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC 211
func NewLocalNedPositionSetpointExternal ¶
func NewLocalNedPositionSetpointExternal(TIME_BOOT_MS uint32, X float32, Y float32, Z float32, VX float32, VY float32, VZ float32, AFX float32, AFY float32, AFZ float32, TYPE_MASK uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, COORDINATE_FRAME uint8) *LocalNedPositionSetpointExternal
NewLocalNedPositionSetpointExternal returns a new LocalNedPositionSetpointExternal
func (*LocalNedPositionSetpointExternal) Crc ¶
func (*LocalNedPositionSetpointExternal) Crc() uint8
Crc returns the LocalNedPositionSetpointExternal Message CRC
func (*LocalNedPositionSetpointExternal) Decode ¶
func (m *LocalNedPositionSetpointExternal) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the LocalNedPositionSetpointExternal
func (*LocalNedPositionSetpointExternal) Id ¶
func (*LocalNedPositionSetpointExternal) Id() uint8
Id returns the LocalNedPositionSetpointExternal Message ID
func (*LocalNedPositionSetpointExternal) Len ¶
func (*LocalNedPositionSetpointExternal) Len() uint8
Len returns the LocalNedPositionSetpointExternal Message Length
func (*LocalNedPositionSetpointExternal) Pack ¶
func (m *LocalNedPositionSetpointExternal) Pack() []byte
Pack returns a packed byte array which represents a LocalNedPositionSetpointExternal payload
type LocalPositionNed ¶
type LocalPositionNed struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) X float32 // X Position Y float32 // Y Position Z float32 // Z Position VX float32 // X Speed VY float32 // Y Speed VZ float32 // Z Speed }
MESSAGE LOCAL_POSITION_NED
MAVLINK_MSG_ID_LOCAL_POSITION_NED 32
MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28
MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185
func NewLocalPositionNed ¶
func NewLocalPositionNed(TIME_BOOT_MS uint32, X float32, Y float32, Z float32, VX float32, VY float32, VZ float32) *LocalPositionNed
NewLocalPositionNed returns a new LocalPositionNed
func (*LocalPositionNed) Crc ¶
func (*LocalPositionNed) Crc() uint8
Crc returns the LocalPositionNed Message CRC
func (*LocalPositionNed) Decode ¶
func (m *LocalPositionNed) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the LocalPositionNed
func (*LocalPositionNed) Id ¶
func (*LocalPositionNed) Id() uint8
Id returns the LocalPositionNed Message ID
func (*LocalPositionNed) Len ¶
func (*LocalPositionNed) Len() uint8
Len returns the LocalPositionNed Message Length
func (*LocalPositionNed) Pack ¶
func (m *LocalPositionNed) Pack() []byte
Pack returns a packed byte array which represents a LocalPositionNed payload
type LocalPositionNedSystemGlobalOffset ¶
type LocalPositionNedSystemGlobalOffset struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) X float32 // X Position Y float32 // Y Position Z float32 // Z Position ROLL float32 // Roll PITCH float32 // Pitch YAW float32 // Yaw }
MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET
MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89
MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28
MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231
func NewLocalPositionNedSystemGlobalOffset ¶
func NewLocalPositionNedSystemGlobalOffset(TIME_BOOT_MS uint32, X float32, Y float32, Z float32, ROLL float32, PITCH float32, YAW float32) *LocalPositionNedSystemGlobalOffset
NewLocalPositionNedSystemGlobalOffset returns a new LocalPositionNedSystemGlobalOffset
func (*LocalPositionNedSystemGlobalOffset) Crc ¶
func (*LocalPositionNedSystemGlobalOffset) Crc() uint8
Crc returns the LocalPositionNedSystemGlobalOffset Message CRC
func (*LocalPositionNedSystemGlobalOffset) Decode ¶
func (m *LocalPositionNedSystemGlobalOffset) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the LocalPositionNedSystemGlobalOffset
func (*LocalPositionNedSystemGlobalOffset) Id ¶
func (*LocalPositionNedSystemGlobalOffset) Id() uint8
Id returns the LocalPositionNedSystemGlobalOffset Message ID
func (*LocalPositionNedSystemGlobalOffset) Len ¶
func (*LocalPositionNedSystemGlobalOffset) Len() uint8
Len returns the LocalPositionNedSystemGlobalOffset Message Length
func (*LocalPositionNedSystemGlobalOffset) Pack ¶
func (m *LocalPositionNedSystemGlobalOffset) Pack() []byte
Pack returns a packed byte array which represents a LocalPositionNedSystemGlobalOffset payload
type LocalPositionSetpoint ¶
type LocalPositionSetpoint struct { X float32 // x position Y float32 // y position Z float32 // z position YAW float32 // Desired yaw angle COORDINATE_FRAME uint8 // Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU }
MESSAGE LOCAL_POSITION_SETPOINT
MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51
MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 17
MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC 223
func NewLocalPositionSetpoint ¶
func NewLocalPositionSetpoint(X float32, Y float32, Z float32, YAW float32, COORDINATE_FRAME uint8) *LocalPositionSetpoint
NewLocalPositionSetpoint returns a new LocalPositionSetpoint
func (*LocalPositionSetpoint) Crc ¶
func (*LocalPositionSetpoint) Crc() uint8
Crc returns the LocalPositionSetpoint Message CRC
func (*LocalPositionSetpoint) Decode ¶
func (m *LocalPositionSetpoint) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the LocalPositionSetpoint
func (*LocalPositionSetpoint) Id ¶
func (*LocalPositionSetpoint) Id() uint8
Id returns the LocalPositionSetpoint Message ID
func (*LocalPositionSetpoint) Len ¶
func (*LocalPositionSetpoint) Len() uint8
Len returns the LocalPositionSetpoint Message Length
func (*LocalPositionSetpoint) Pack ¶
func (m *LocalPositionSetpoint) Pack() []byte
Pack returns a packed byte array which represents a LocalPositionSetpoint payload
type LogData ¶
type LogData struct { OFS uint32 // Offset into the log ID uint16 // Log id (from LOG_ENTRY reply) COUNT uint8 // Number of bytes (zero for end of log) DATA [90]uint8 // log data }
MESSAGE LOG_DATA
MAVLINK_MSG_ID_LOG_DATA 120
MAVLINK_MSG_ID_LOG_DATA_LEN 97
MAVLINK_MSG_ID_LOG_DATA_CRC 134
func NewLogData ¶
NewLogData returns a new LogData
type LogEntry ¶
type LogEntry struct { TIME_UTC uint32 // UTC timestamp of log in seconds since 1970, or 0 if not available SIZE uint32 // Size of the log (may be approximate) in bytes ID uint16 // Log id NUM_LOGS uint16 // Total number of logs LAST_LOG_NUM uint16 // High log number }
MESSAGE LOG_ENTRY
MAVLINK_MSG_ID_LOG_ENTRY 118
MAVLINK_MSG_ID_LOG_ENTRY_LEN 14
MAVLINK_MSG_ID_LOG_ENTRY_CRC 56
func NewLogEntry ¶
func NewLogEntry(TIME_UTC uint32, SIZE uint32, ID uint16, NUM_LOGS uint16, LAST_LOG_NUM uint16) *LogEntry
NewLogEntry returns a new LogEntry
type LogErase ¶
MESSAGE LOG_ERASE
MAVLINK_MSG_ID_LOG_ERASE 121
MAVLINK_MSG_ID_LOG_ERASE_LEN 2
MAVLINK_MSG_ID_LOG_ERASE_CRC 237
func NewLogErase ¶
NewLogErase returns a new LogErase
type LogRequestData ¶
type LogRequestData struct { OFS uint32 // Offset into the log COUNT uint32 // Number of bytes ID uint16 // Log id (from LOG_ENTRY reply) TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE LOG_REQUEST_DATA
MAVLINK_MSG_ID_LOG_REQUEST_DATA 119
MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12
MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116
func NewLogRequestData ¶
func NewLogRequestData(OFS uint32, COUNT uint32, ID uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *LogRequestData
NewLogRequestData returns a new LogRequestData
func (*LogRequestData) Crc ¶
func (*LogRequestData) Crc() uint8
Crc returns the LogRequestData Message CRC
func (*LogRequestData) Decode ¶
func (m *LogRequestData) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the LogRequestData
func (*LogRequestData) Id ¶
func (*LogRequestData) Id() uint8
Id returns the LogRequestData Message ID
func (*LogRequestData) Len ¶
func (*LogRequestData) Len() uint8
Len returns the LogRequestData Message Length
func (*LogRequestData) Pack ¶
func (m *LogRequestData) Pack() []byte
Pack returns a packed byte array which represents a LogRequestData payload
type LogRequestEnd ¶
type LogRequestEnd struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE LOG_REQUEST_END
MAVLINK_MSG_ID_LOG_REQUEST_END 122
MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2
MAVLINK_MSG_ID_LOG_REQUEST_END_CRC 203
func NewLogRequestEnd ¶
func NewLogRequestEnd(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *LogRequestEnd
NewLogRequestEnd returns a new LogRequestEnd
func (*LogRequestEnd) Crc ¶
func (*LogRequestEnd) Crc() uint8
Crc returns the LogRequestEnd Message CRC
func (*LogRequestEnd) Decode ¶
func (m *LogRequestEnd) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the LogRequestEnd
func (*LogRequestEnd) Len ¶
func (*LogRequestEnd) Len() uint8
Len returns the LogRequestEnd Message Length
func (*LogRequestEnd) Pack ¶
func (m *LogRequestEnd) Pack() []byte
Pack returns a packed byte array which represents a LogRequestEnd payload
type LogRequestList ¶
type LogRequestList struct { START uint16 // First log id (0 for first available) END uint16 // Last log id (0xffff for last available) TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE LOG_REQUEST_LIST
MAVLINK_MSG_ID_LOG_REQUEST_LIST 117
MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6
MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC 128
func NewLogRequestList ¶
func NewLogRequestList(START uint16, END uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *LogRequestList
NewLogRequestList returns a new LogRequestList
func (*LogRequestList) Crc ¶
func (*LogRequestList) Crc() uint8
Crc returns the LogRequestList Message CRC
func (*LogRequestList) Decode ¶
func (m *LogRequestList) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the LogRequestList
func (*LogRequestList) Id ¶
func (*LogRequestList) Id() uint8
Id returns the LogRequestList Message ID
func (*LogRequestList) Len ¶
func (*LogRequestList) Len() uint8
Len returns the LogRequestList Message Length
func (*LogRequestList) Pack ¶
func (m *LogRequestList) Pack() []byte
Pack returns a packed byte array which represents a LogRequestList payload
type MAVLinkMessage ¶
The MAVLinkMessage interface is implemented by MAVLink messages
func NewMAVLinkMessage ¶
func NewMAVLinkMessage(msgid uint8, data []byte) (MAVLinkMessage, error)
NewMAVLinkMessage returns a new MAVLinkMessage or an error if it encounters an unknown Message ID
type MAVLinkPacket ¶
type MAVLinkPacket struct { Protocol uint8 Length uint8 Sequence uint8 SystemID uint8 ComponentID uint8 MessageID uint8 Data []uint8 Checksum uint16 }
A MAVLinkPacket represents a raw packet received from a micro air vehicle
func CraftMAVLinkPacket ¶
func CraftMAVLinkPacket(SystemID uint8, ComponentID uint8, Message MAVLinkMessage) *MAVLinkPacket
CraftMAVLinkPacket returns a new MAVLinkPacket from a MAVLinkMessage
func NewMAVLinkPacket ¶
func NewMAVLinkPacket(Protocol uint8, Length uint8, Sequence uint8, SystemID uint8, ComponentID uint8, MessageID uint8, Data []uint8) *MAVLinkPacket
NewMAVLinkPacket returns a new MAVLinkPacket
func ReadMAVLinkPacket ¶
func ReadMAVLinkPacket(r io.Reader) (*MAVLinkPacket, error)
ReadMAVLinkPacket reads an io.Reader for a new packet and returns a new MAVLink packet or returns the error received by the io.Reader
func (*MAVLinkPacket) Decode ¶
func (m *MAVLinkPacket) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MAVLinkPacket
func (*MAVLinkPacket) MAVLinkMessage ¶
func (m *MAVLinkPacket) MAVLinkMessage() (MAVLinkMessage, error)
MAVLinkMessage returns the decoded MAVLinkMessage from the MAVLinkPacket or returns an error generated from the MAVLinkMessage
func (*MAVLinkPacket) Pack ¶
func (m *MAVLinkPacket) Pack() []byte
Pack returns a packed byte array which represents the MAVLinkPacket
type ManualControl ¶
type ManualControl struct { X int16 // X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. Y int16 // Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. Z int16 // Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. R int16 // R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. BUTTONS uint16 // A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. TARGET uint8 // The system to be controlled. }
MESSAGE MANUAL_CONTROL
MAVLINK_MSG_ID_MANUAL_CONTROL 69
MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11
MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243
func NewManualControl ¶
func NewManualControl(X int16, Y int16, Z int16, R int16, BUTTONS uint16, TARGET uint8) *ManualControl
NewManualControl returns a new ManualControl
func (*ManualControl) Crc ¶
func (*ManualControl) Crc() uint8
Crc returns the ManualControl Message CRC
func (*ManualControl) Decode ¶
func (m *ManualControl) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the ManualControl
func (*ManualControl) Len ¶
func (*ManualControl) Len() uint8
Len returns the ManualControl Message Length
func (*ManualControl) Pack ¶
func (m *ManualControl) Pack() []byte
Pack returns a packed byte array which represents a ManualControl payload
type ManualSetpoint ¶
type ManualSetpoint struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot ROLL float32 // Desired roll rate in radians per second PITCH float32 // Desired pitch rate in radians per second YAW float32 // Desired yaw rate in radians per second THRUST float32 // Collective thrust, normalized to 0 .. 1 MODE_SWITCH uint8 // Flight mode switch position, 0.. 255 MANUAL_OVERRIDE_SWITCH uint8 // Override mode switch position, 0.. 255 }
MESSAGE MANUAL_SETPOINT
MAVLINK_MSG_ID_MANUAL_SETPOINT 81
MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22
MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC 106
func NewManualSetpoint ¶
func NewManualSetpoint(TIME_BOOT_MS uint32, ROLL float32, PITCH float32, YAW float32, THRUST float32, MODE_SWITCH uint8, MANUAL_OVERRIDE_SWITCH uint8) *ManualSetpoint
NewManualSetpoint returns a new ManualSetpoint
func (*ManualSetpoint) Crc ¶
func (*ManualSetpoint) Crc() uint8
Crc returns the ManualSetpoint Message CRC
func (*ManualSetpoint) Decode ¶
func (m *ManualSetpoint) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the ManualSetpoint
func (*ManualSetpoint) Id ¶
func (*ManualSetpoint) Id() uint8
Id returns the ManualSetpoint Message ID
func (*ManualSetpoint) Len ¶
func (*ManualSetpoint) Len() uint8
Len returns the ManualSetpoint Message Length
func (*ManualSetpoint) Pack ¶
func (m *ManualSetpoint) Pack() []byte
Pack returns a packed byte array which represents a ManualSetpoint payload
type MemoryVect ¶
type MemoryVect struct { ADDRESS uint16 // Starting address of the debug variables VER uint8 // Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below TYPE uint8 // Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 VALUE [32]int8 // Memory contents at specified address }
MESSAGE MEMORY_VECT
MAVLINK_MSG_ID_MEMORY_VECT 249
MAVLINK_MSG_ID_MEMORY_VECT_LEN 36
MAVLINK_MSG_ID_MEMORY_VECT_CRC 204
func NewMemoryVect ¶
func NewMemoryVect(ADDRESS uint16, VER uint8, TYPE uint8, VALUE [32]int8) *MemoryVect
NewMemoryVect returns a new MemoryVect
func (*MemoryVect) Decode ¶
func (m *MemoryVect) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MemoryVect
func (*MemoryVect) Pack ¶
func (m *MemoryVect) Pack() []byte
Pack returns a packed byte array which represents a MemoryVect payload
type MissionAck ¶
type MissionAck struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID TYPE uint8 // See MAV_MISSION_RESULT enum }
MESSAGE MISSION_ACK
MAVLINK_MSG_ID_MISSION_ACK 47
MAVLINK_MSG_ID_MISSION_ACK_LEN 3
MAVLINK_MSG_ID_MISSION_ACK_CRC 153
func NewMissionAck ¶
func NewMissionAck(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, TYPE uint8) *MissionAck
NewMissionAck returns a new MissionAck
func (*MissionAck) Decode ¶
func (m *MissionAck) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MissionAck
func (*MissionAck) Pack ¶
func (m *MissionAck) Pack() []byte
Pack returns a packed byte array which represents a MissionAck payload
type MissionClearAll ¶
type MissionClearAll struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE MISSION_CLEAR_ALL
MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45
MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2
MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC 232
func NewMissionClearAll ¶
func NewMissionClearAll(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionClearAll
NewMissionClearAll returns a new MissionClearAll
func (*MissionClearAll) Crc ¶
func (*MissionClearAll) Crc() uint8
Crc returns the MissionClearAll Message CRC
func (*MissionClearAll) Decode ¶
func (m *MissionClearAll) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MissionClearAll
func (*MissionClearAll) Id ¶
func (*MissionClearAll) Id() uint8
Id returns the MissionClearAll Message ID
func (*MissionClearAll) Len ¶
func (*MissionClearAll) Len() uint8
Len returns the MissionClearAll Message Length
func (*MissionClearAll) Pack ¶
func (m *MissionClearAll) Pack() []byte
Pack returns a packed byte array which represents a MissionClearAll payload
type MissionCount ¶
type MissionCount struct { COUNT uint16 // Number of mission items in the sequence TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE MISSION_COUNT
MAVLINK_MSG_ID_MISSION_COUNT 44
MAVLINK_MSG_ID_MISSION_COUNT_LEN 4
MAVLINK_MSG_ID_MISSION_COUNT_CRC 221
func NewMissionCount ¶
func NewMissionCount(COUNT uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionCount
NewMissionCount returns a new MissionCount
func (*MissionCount) Crc ¶
func (*MissionCount) Crc() uint8
Crc returns the MissionCount Message CRC
func (*MissionCount) Decode ¶
func (m *MissionCount) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MissionCount
func (*MissionCount) Len ¶
func (*MissionCount) Len() uint8
Len returns the MissionCount Message Length
func (*MissionCount) Pack ¶
func (m *MissionCount) Pack() []byte
Pack returns a packed byte array which represents a MissionCount payload
type MissionCurrent ¶
type MissionCurrent struct {
SEQ uint16 // Sequence
}
MESSAGE MISSION_CURRENT
MAVLINK_MSG_ID_MISSION_CURRENT 42
MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2
MAVLINK_MSG_ID_MISSION_CURRENT_CRC 28
func NewMissionCurrent ¶
func NewMissionCurrent(SEQ uint16) *MissionCurrent
NewMissionCurrent returns a new MissionCurrent
func (*MissionCurrent) Crc ¶
func (*MissionCurrent) Crc() uint8
Crc returns the MissionCurrent Message CRC
func (*MissionCurrent) Decode ¶
func (m *MissionCurrent) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MissionCurrent
func (*MissionCurrent) Id ¶
func (*MissionCurrent) Id() uint8
Id returns the MissionCurrent Message ID
func (*MissionCurrent) Len ¶
func (*MissionCurrent) Len() uint8
Len returns the MissionCurrent Message Length
func (*MissionCurrent) Pack ¶
func (m *MissionCurrent) Pack() []byte
Pack returns a packed byte array which represents a MissionCurrent payload
type MissionItem ¶
type MissionItem struct { PARAM1 float32 // PARAM1, see MAV_CMD enum PARAM2 float32 // PARAM2, see MAV_CMD enum PARAM3 float32 // PARAM3, see MAV_CMD enum PARAM4 float32 // PARAM4, see MAV_CMD enum X float32 // PARAM5 / local: x position, global: latitude Y float32 // PARAM6 / y position: global: longitude Z float32 // PARAM7 / z position: global: altitude (relative or absolute, depending on frame. SEQ uint16 // Sequence COMMAND uint16 // The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID FRAME uint8 // The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h CURRENT uint8 // false:0, true:1 AUTOCONTINUE uint8 // autocontinue to next wp }
MESSAGE MISSION_ITEM
MAVLINK_MSG_ID_MISSION_ITEM 39
MAVLINK_MSG_ID_MISSION_ITEM_LEN 37
MAVLINK_MSG_ID_MISSION_ITEM_CRC 254
func NewMissionItem ¶
func NewMissionItem(PARAM1 float32, PARAM2 float32, PARAM3 float32, PARAM4 float32, X float32, Y float32, Z float32, SEQ uint16, COMMAND uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, FRAME uint8, CURRENT uint8, AUTOCONTINUE uint8) *MissionItem
NewMissionItem returns a new MissionItem
func (*MissionItem) Decode ¶
func (m *MissionItem) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MissionItem
func (*MissionItem) Len ¶
func (*MissionItem) Len() uint8
Len returns the MissionItem Message Length
func (*MissionItem) Pack ¶
func (m *MissionItem) Pack() []byte
Pack returns a packed byte array which represents a MissionItem payload
type MissionItemReached ¶
type MissionItemReached struct {
SEQ uint16 // Sequence
}
MESSAGE MISSION_ITEM_REACHED
MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46
MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2
MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC 11
func NewMissionItemReached ¶
func NewMissionItemReached(SEQ uint16) *MissionItemReached
NewMissionItemReached returns a new MissionItemReached
func (*MissionItemReached) Crc ¶
func (*MissionItemReached) Crc() uint8
Crc returns the MissionItemReached Message CRC
func (*MissionItemReached) Decode ¶
func (m *MissionItemReached) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MissionItemReached
func (*MissionItemReached) Id ¶
func (*MissionItemReached) Id() uint8
Id returns the MissionItemReached Message ID
func (*MissionItemReached) Len ¶
func (*MissionItemReached) Len() uint8
Len returns the MissionItemReached Message Length
func (*MissionItemReached) Pack ¶
func (m *MissionItemReached) Pack() []byte
Pack returns a packed byte array which represents a MissionItemReached payload
type MissionRequest ¶
type MissionRequest struct { SEQ uint16 // Sequence TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE MISSION_REQUEST
MAVLINK_MSG_ID_MISSION_REQUEST 40
MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4
MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230
func NewMissionRequest ¶
func NewMissionRequest(SEQ uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionRequest
NewMissionRequest returns a new MissionRequest
func (*MissionRequest) Crc ¶
func (*MissionRequest) Crc() uint8
Crc returns the MissionRequest Message CRC
func (*MissionRequest) Decode ¶
func (m *MissionRequest) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MissionRequest
func (*MissionRequest) Id ¶
func (*MissionRequest) Id() uint8
Id returns the MissionRequest Message ID
func (*MissionRequest) Len ¶
func (*MissionRequest) Len() uint8
Len returns the MissionRequest Message Length
func (*MissionRequest) Pack ¶
func (m *MissionRequest) Pack() []byte
Pack returns a packed byte array which represents a MissionRequest payload
type MissionRequestList ¶
type MissionRequestList struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE MISSION_REQUEST_LIST
MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43
MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2
MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC 132
func NewMissionRequestList ¶
func NewMissionRequestList(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionRequestList
NewMissionRequestList returns a new MissionRequestList
func (*MissionRequestList) Crc ¶
func (*MissionRequestList) Crc() uint8
Crc returns the MissionRequestList Message CRC
func (*MissionRequestList) Decode ¶
func (m *MissionRequestList) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MissionRequestList
func (*MissionRequestList) Id ¶
func (*MissionRequestList) Id() uint8
Id returns the MissionRequestList Message ID
func (*MissionRequestList) Len ¶
func (*MissionRequestList) Len() uint8
Len returns the MissionRequestList Message Length
func (*MissionRequestList) Pack ¶
func (m *MissionRequestList) Pack() []byte
Pack returns a packed byte array which represents a MissionRequestList payload
type MissionRequestPartialList ¶
type MissionRequestPartialList struct { START_INDEX int16 // Start index, 0 by default END_INDEX int16 // End index, -1 by default (-1: send list to end). Else a valid index of the list TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE MISSION_REQUEST_PARTIAL_LIST
MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37
MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6
MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212
func NewMissionRequestPartialList ¶
func NewMissionRequestPartialList(START_INDEX int16, END_INDEX int16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionRequestPartialList
NewMissionRequestPartialList returns a new MissionRequestPartialList
func (*MissionRequestPartialList) Crc ¶
func (*MissionRequestPartialList) Crc() uint8
Crc returns the MissionRequestPartialList Message CRC
func (*MissionRequestPartialList) Decode ¶
func (m *MissionRequestPartialList) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MissionRequestPartialList
func (*MissionRequestPartialList) Id ¶
func (*MissionRequestPartialList) Id() uint8
Id returns the MissionRequestPartialList Message ID
func (*MissionRequestPartialList) Len ¶
func (*MissionRequestPartialList) Len() uint8
Len returns the MissionRequestPartialList Message Length
func (*MissionRequestPartialList) Pack ¶
func (m *MissionRequestPartialList) Pack() []byte
Pack returns a packed byte array which represents a MissionRequestPartialList payload
type MissionSetCurrent ¶
type MissionSetCurrent struct { SEQ uint16 // Sequence TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE MISSION_SET_CURRENT
MAVLINK_MSG_ID_MISSION_SET_CURRENT 41
MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4
MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC 28
func NewMissionSetCurrent ¶
func NewMissionSetCurrent(SEQ uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionSetCurrent
NewMissionSetCurrent returns a new MissionSetCurrent
func (*MissionSetCurrent) Crc ¶
func (*MissionSetCurrent) Crc() uint8
Crc returns the MissionSetCurrent Message CRC
func (*MissionSetCurrent) Decode ¶
func (m *MissionSetCurrent) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MissionSetCurrent
func (*MissionSetCurrent) Id ¶
func (*MissionSetCurrent) Id() uint8
Id returns the MissionSetCurrent Message ID
func (*MissionSetCurrent) Len ¶
func (*MissionSetCurrent) Len() uint8
Len returns the MissionSetCurrent Message Length
func (*MissionSetCurrent) Pack ¶
func (m *MissionSetCurrent) Pack() []byte
Pack returns a packed byte array which represents a MissionSetCurrent payload
type MissionWritePartialList ¶
type MissionWritePartialList struct { START_INDEX int16 // Start index, 0 by default and smaller / equal to the largest index of the current onboard list. END_INDEX int16 // End index, equal or greater than start index. TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE MISSION_WRITE_PARTIAL_LIST
MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38
MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6
MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9
func NewMissionWritePartialList ¶
func NewMissionWritePartialList(START_INDEX int16, END_INDEX int16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionWritePartialList
NewMissionWritePartialList returns a new MissionWritePartialList
func (*MissionWritePartialList) Crc ¶
func (*MissionWritePartialList) Crc() uint8
Crc returns the MissionWritePartialList Message CRC
func (*MissionWritePartialList) Decode ¶
func (m *MissionWritePartialList) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the MissionWritePartialList
func (*MissionWritePartialList) Id ¶
func (*MissionWritePartialList) Id() uint8
Id returns the MissionWritePartialList Message ID
func (*MissionWritePartialList) Len ¶
func (*MissionWritePartialList) Len() uint8
Len returns the MissionWritePartialList Message Length
func (*MissionWritePartialList) Pack ¶
func (m *MissionWritePartialList) Pack() []byte
Pack returns a packed byte array which represents a MissionWritePartialList payload
type NamedValueFloat ¶
type NamedValueFloat struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) VALUE float32 // Floating point value NAME [10]uint8 // Name of the debug variable }
MESSAGE NAMED_VALUE_FLOAT
MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251
MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18
MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC 170
func NewNamedValueFloat ¶
func NewNamedValueFloat(TIME_BOOT_MS uint32, VALUE float32, NAME [10]uint8) *NamedValueFloat
NewNamedValueFloat returns a new NamedValueFloat
func (*NamedValueFloat) Crc ¶
func (*NamedValueFloat) Crc() uint8
Crc returns the NamedValueFloat Message CRC
func (*NamedValueFloat) Decode ¶
func (m *NamedValueFloat) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the NamedValueFloat
func (*NamedValueFloat) Id ¶
func (*NamedValueFloat) Id() uint8
Id returns the NamedValueFloat Message ID
func (*NamedValueFloat) Len ¶
func (*NamedValueFloat) Len() uint8
Len returns the NamedValueFloat Message Length
func (*NamedValueFloat) Pack ¶
func (m *NamedValueFloat) Pack() []byte
Pack returns a packed byte array which represents a NamedValueFloat payload
type NamedValueInt ¶
type NamedValueInt struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) VALUE int32 // Signed integer value NAME [10]uint8 // Name of the debug variable }
MESSAGE NAMED_VALUE_INT
MAVLINK_MSG_ID_NAMED_VALUE_INT 252
MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18
MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC 44
func NewNamedValueInt ¶
func NewNamedValueInt(TIME_BOOT_MS uint32, VALUE int32, NAME [10]uint8) *NamedValueInt
NewNamedValueInt returns a new NamedValueInt
func (*NamedValueInt) Crc ¶
func (*NamedValueInt) Crc() uint8
Crc returns the NamedValueInt Message CRC
func (*NamedValueInt) Decode ¶
func (m *NamedValueInt) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the NamedValueInt
func (*NamedValueInt) Len ¶
func (*NamedValueInt) Len() uint8
Len returns the NamedValueInt Message Length
func (*NamedValueInt) Pack ¶
func (m *NamedValueInt) Pack() []byte
Pack returns a packed byte array which represents a NamedValueInt payload
type NavControllerOutput ¶
type NavControllerOutput struct {}
MESSAGE NAV_CONTROLLER_OUTPUT
MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62
MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26
MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183
func NewNavControllerOutput ¶
func NewNavControllerOutput(NAV_ROLL float32, NAV_PITCH float32, ALT_ERROR float32, ASPD_ERROR float32, XTRACK_ERROR float32, NAV_BEARING int16, TARGET_BEARING int16, WP_DIST uint16) *NavControllerOutput
NewNavControllerOutput returns a new NavControllerOutput
func (*NavControllerOutput) Crc ¶
func (*NavControllerOutput) Crc() uint8
Crc returns the NavControllerOutput Message CRC
func (*NavControllerOutput) Decode ¶
func (m *NavControllerOutput) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the NavControllerOutput
func (*NavControllerOutput) Id ¶
func (*NavControllerOutput) Id() uint8
Id returns the NavControllerOutput Message ID
func (*NavControllerOutput) Len ¶
func (*NavControllerOutput) Len() uint8
Len returns the NavControllerOutput Message Length
func (*NavControllerOutput) Pack ¶
func (m *NavControllerOutput) Pack() []byte
Pack returns a packed byte array which represents a NavControllerOutput payload
type OmnidirectionalFlow ¶
type OmnidirectionalFlow struct { TIME_USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) FRONT_DISTANCE_M float32 // Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance LEFT [10]int16 // Flow in deci pixels (1 = 0.1 pixel) on left hemisphere RIGHT [10]int16 // Flow in deci pixels (1 = 0.1 pixel) on right hemisphere SENSOR_ID uint8 // Sensor ID QUALITY uint8 // Optical flow quality / confidence. 0: bad, 255: maximum quality }
MESSAGE OMNIDIRECTIONAL_FLOW
MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW 106
MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN 54
MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC 211
func NewOmnidirectionalFlow ¶
func NewOmnidirectionalFlow(TIME_USEC uint64, FRONT_DISTANCE_M float32, LEFT [10]int16, RIGHT [10]int16, SENSOR_ID uint8, QUALITY uint8) *OmnidirectionalFlow
NewOmnidirectionalFlow returns a new OmnidirectionalFlow
func (*OmnidirectionalFlow) Crc ¶
func (*OmnidirectionalFlow) Crc() uint8
Crc returns the OmnidirectionalFlow Message CRC
func (*OmnidirectionalFlow) Decode ¶
func (m *OmnidirectionalFlow) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the OmnidirectionalFlow
func (*OmnidirectionalFlow) Id ¶
func (*OmnidirectionalFlow) Id() uint8
Id returns the OmnidirectionalFlow Message ID
func (*OmnidirectionalFlow) Len ¶
func (*OmnidirectionalFlow) Len() uint8
Len returns the OmnidirectionalFlow Message Length
func (*OmnidirectionalFlow) Pack ¶
func (m *OmnidirectionalFlow) Pack() []byte
Pack returns a packed byte array which represents a OmnidirectionalFlow payload
type OpticalFlow ¶
type OpticalFlow struct { TIME_USEC uint64 // Timestamp (UNIX) FLOW_COMP_M_X float32 // Flow in meters in x-sensor direction, angular-speed compensated FLOW_COMP_M_Y float32 // Flow in meters in y-sensor direction, angular-speed compensated GROUND_DISTANCE float32 // Ground distance in meters. Positive value: distance known. Negative value: Unknown distance FLOW_X int16 // Flow in pixels * 10 in x-sensor direction (dezi-pixels) FLOW_Y int16 // Flow in pixels * 10 in y-sensor direction (dezi-pixels) SENSOR_ID uint8 // Sensor ID QUALITY uint8 // Optical flow quality / confidence. 0: bad, 255: maximum quality }
MESSAGE OPTICAL_FLOW
MAVLINK_MSG_ID_OPTICAL_FLOW 100
MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26
MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175
func NewOpticalFlow ¶
func NewOpticalFlow(TIME_USEC uint64, FLOW_COMP_M_X float32, FLOW_COMP_M_Y float32, GROUND_DISTANCE float32, FLOW_X int16, FLOW_Y int16, SENSOR_ID uint8, QUALITY uint8) *OpticalFlow
NewOpticalFlow returns a new OpticalFlow
func (*OpticalFlow) Decode ¶
func (m *OpticalFlow) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the OpticalFlow
func (*OpticalFlow) Len ¶
func (*OpticalFlow) Len() uint8
Len returns the OpticalFlow Message Length
func (*OpticalFlow) Pack ¶
func (m *OpticalFlow) Pack() []byte
Pack returns a packed byte array which represents a OpticalFlow payload
type ParamRequestList ¶
type ParamRequestList struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE PARAM_REQUEST_LIST
MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21
MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2
MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC 159
func NewParamRequestList ¶
func NewParamRequestList(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *ParamRequestList
NewParamRequestList returns a new ParamRequestList
func (*ParamRequestList) Crc ¶
func (*ParamRequestList) Crc() uint8
Crc returns the ParamRequestList Message CRC
func (*ParamRequestList) Decode ¶
func (m *ParamRequestList) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the ParamRequestList
func (*ParamRequestList) Id ¶
func (*ParamRequestList) Id() uint8
Id returns the ParamRequestList Message ID
func (*ParamRequestList) Len ¶
func (*ParamRequestList) Len() uint8
Len returns the ParamRequestList Message Length
func (*ParamRequestList) Pack ¶
func (m *ParamRequestList) Pack() []byte
Pack returns a packed byte array which represents a ParamRequestList payload
type ParamRequestRead ¶
type ParamRequestRead struct { PARAM_INDEX int16 // Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID PARAM_ID [16]uint8 // Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string }
MESSAGE PARAM_REQUEST_READ
MAVLINK_MSG_ID_PARAM_REQUEST_READ 20
MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20
MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214
func NewParamRequestRead ¶
func NewParamRequestRead(PARAM_INDEX int16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, PARAM_ID [16]uint8) *ParamRequestRead
NewParamRequestRead returns a new ParamRequestRead
func (*ParamRequestRead) Crc ¶
func (*ParamRequestRead) Crc() uint8
Crc returns the ParamRequestRead Message CRC
func (*ParamRequestRead) Decode ¶
func (m *ParamRequestRead) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the ParamRequestRead
func (*ParamRequestRead) Id ¶
func (*ParamRequestRead) Id() uint8
Id returns the ParamRequestRead Message ID
func (*ParamRequestRead) Len ¶
func (*ParamRequestRead) Len() uint8
Len returns the ParamRequestRead Message Length
func (*ParamRequestRead) Pack ¶
func (m *ParamRequestRead) Pack() []byte
Pack returns a packed byte array which represents a ParamRequestRead payload
type ParamSet ¶
type ParamSet struct { PARAM_VALUE float32 // Onboard parameter value TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID PARAM_ID [16]uint8 // Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string PARAM_TYPE uint8 // Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. }
MESSAGE PARAM_SET
MAVLINK_MSG_ID_PARAM_SET 23
MAVLINK_MSG_ID_PARAM_SET_LEN 23
MAVLINK_MSG_ID_PARAM_SET_CRC 168
func NewParamSet ¶
func NewParamSet(PARAM_VALUE float32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, PARAM_ID [16]uint8, PARAM_TYPE uint8) *ParamSet
NewParamSet returns a new ParamSet
type ParamValue ¶
type ParamValue struct { PARAM_VALUE float32 // Onboard parameter value PARAM_COUNT uint16 // Total number of onboard parameters PARAM_INDEX uint16 // Index of this onboard parameter PARAM_ID [16]uint8 // Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string PARAM_TYPE uint8 // Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. }
MESSAGE PARAM_VALUE
MAVLINK_MSG_ID_PARAM_VALUE 22
MAVLINK_MSG_ID_PARAM_VALUE_LEN 25
MAVLINK_MSG_ID_PARAM_VALUE_CRC 220
func NewParamValue ¶
func NewParamValue(PARAM_VALUE float32, PARAM_COUNT uint16, PARAM_INDEX uint16, PARAM_ID [16]uint8, PARAM_TYPE uint8) *ParamValue
NewParamValue returns a new ParamValue
func (*ParamValue) Decode ¶
func (m *ParamValue) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the ParamValue
func (*ParamValue) Pack ¶
func (m *ParamValue) Pack() []byte
Pack returns a packed byte array which represents a ParamValue payload
type Ping ¶
type Ping struct { TIME_USEC uint64 // Unix timestamp in microseconds SEQ uint32 // PING sequence TARGET_SYSTEM uint8 // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system TARGET_COMPONENT uint8 // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system }
MESSAGE PING
MAVLINK_MSG_ID_PING 4
MAVLINK_MSG_ID_PING_LEN 14
MAVLINK_MSG_ID_PING_CRC 237
type PowerStatus ¶
type PowerStatus struct { VCC uint16 // 5V rail voltage in millivolts VSERVO uint16 // servo rail voltage in millivolts FLAGS uint16 // power supply status flags (see MAV_POWER_STATUS enum) }
MESSAGE POWER_STATUS
MAVLINK_MSG_ID_POWER_STATUS 125
MAVLINK_MSG_ID_POWER_STATUS_LEN 6
MAVLINK_MSG_ID_POWER_STATUS_CRC 203
func NewPowerStatus ¶
func NewPowerStatus(VCC uint16, VSERVO uint16, FLAGS uint16) *PowerStatus
NewPowerStatus returns a new PowerStatus
func (*PowerStatus) Decode ¶
func (m *PowerStatus) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the PowerStatus
func (*PowerStatus) Len ¶
func (*PowerStatus) Len() uint8
Len returns the PowerStatus Message Length
func (*PowerStatus) Pack ¶
func (m *PowerStatus) Pack() []byte
Pack returns a packed byte array which represents a PowerStatus payload
type RadioStatus ¶
type RadioStatus struct { RXERRORS uint16 // receive errors FIXED uint16 // count of error corrected packets RSSI uint8 // local signal strength REMRSSI uint8 // remote signal strength TXBUF uint8 // how full the tx buffer is as a percentage NOISE uint8 // background noise level REMNOISE uint8 // remote background noise level }
MESSAGE RADIO_STATUS
MAVLINK_MSG_ID_RADIO_STATUS 109
MAVLINK_MSG_ID_RADIO_STATUS_LEN 9
MAVLINK_MSG_ID_RADIO_STATUS_CRC 185
func NewRadioStatus ¶
func NewRadioStatus(RXERRORS uint16, FIXED uint16, RSSI uint8, REMRSSI uint8, TXBUF uint8, NOISE uint8, REMNOISE uint8) *RadioStatus
NewRadioStatus returns a new RadioStatus
func (*RadioStatus) Decode ¶
func (m *RadioStatus) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the RadioStatus
func (*RadioStatus) Len ¶
func (*RadioStatus) Len() uint8
Len returns the RadioStatus Message Length
func (*RadioStatus) Pack ¶
func (m *RadioStatus) Pack() []byte
Pack returns a packed byte array which represents a RadioStatus payload
type RawImu ¶
type RawImu struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) XACC int16 // X acceleration (raw) YACC int16 // Y acceleration (raw) ZACC int16 // Z acceleration (raw) XGYRO int16 // Angular speed around X axis (raw) YGYRO int16 // Angular speed around Y axis (raw) ZGYRO int16 // Angular speed around Z axis (raw) XMAG int16 // X Magnetic field (raw) YMAG int16 // Y Magnetic field (raw) ZMAG int16 // Z Magnetic field (raw) }
MESSAGE RAW_IMU
MAVLINK_MSG_ID_RAW_IMU 27
MAVLINK_MSG_ID_RAW_IMU_LEN 26
MAVLINK_MSG_ID_RAW_IMU_CRC 144
func NewRawImu ¶
func NewRawImu(TIME_USEC uint64, XACC int16, YACC int16, ZACC int16, XGYRO int16, YGYRO int16, ZGYRO int16, XMAG int16, YMAG int16, ZMAG int16) *RawImu
NewRawImu returns a new RawImu
type RawPressure ¶
type RawPressure struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) PRESS_ABS int16 // Absolute pressure (raw) PRESS_DIFF1 int16 // Differential pressure 1 (raw) PRESS_DIFF2 int16 // Differential pressure 2 (raw) TEMPERATURE int16 // Raw Temperature measurement (raw) }
MESSAGE RAW_PRESSURE
MAVLINK_MSG_ID_RAW_PRESSURE 28
MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16
MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67
func NewRawPressure ¶
func NewRawPressure(TIME_USEC uint64, PRESS_ABS int16, PRESS_DIFF1 int16, PRESS_DIFF2 int16, TEMPERATURE int16) *RawPressure
NewRawPressure returns a new RawPressure
func (*RawPressure) Decode ¶
func (m *RawPressure) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the RawPressure
func (*RawPressure) Len ¶
func (*RawPressure) Len() uint8
Len returns the RawPressure Message Length
func (*RawPressure) Pack ¶
func (m *RawPressure) Pack() []byte
Pack returns a packed byte array which represents a RawPressure payload
type RcChannels ¶
type RcChannels struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) CHAN1_RAW uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN2_RAW uint16 // RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN3_RAW uint16 // RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN4_RAW uint16 // RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN5_RAW uint16 // RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN6_RAW uint16 // RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN7_RAW uint16 // RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN8_RAW uint16 // RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN9_RAW uint16 // RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN10_RAW uint16 // RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN11_RAW uint16 // RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN12_RAW uint16 // RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN13_RAW uint16 // RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN14_RAW uint16 // RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN15_RAW uint16 // RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN16_RAW uint16 // RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN17_RAW uint16 // RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN18_RAW uint16 // RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHANCOUNT uint8 // Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. RSSI uint8 // Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. }
MESSAGE RC_CHANNELS
MAVLINK_MSG_ID_RC_CHANNELS 65
MAVLINK_MSG_ID_RC_CHANNELS_LEN 42
MAVLINK_MSG_ID_RC_CHANNELS_CRC 118
func NewRcChannels ¶
func NewRcChannels(TIME_BOOT_MS uint32, CHAN1_RAW uint16, CHAN2_RAW uint16, CHAN3_RAW uint16, CHAN4_RAW uint16, CHAN5_RAW uint16, CHAN6_RAW uint16, CHAN7_RAW uint16, CHAN8_RAW uint16, CHAN9_RAW uint16, CHAN10_RAW uint16, CHAN11_RAW uint16, CHAN12_RAW uint16, CHAN13_RAW uint16, CHAN14_RAW uint16, CHAN15_RAW uint16, CHAN16_RAW uint16, CHAN17_RAW uint16, CHAN18_RAW uint16, CHANCOUNT uint8, RSSI uint8) *RcChannels
NewRcChannels returns a new RcChannels
func (*RcChannels) Decode ¶
func (m *RcChannels) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the RcChannels
func (*RcChannels) Pack ¶
func (m *RcChannels) Pack() []byte
Pack returns a packed byte array which represents a RcChannels payload
type RcChannelsOverride ¶
type RcChannelsOverride struct { CHAN1_RAW uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. CHAN2_RAW uint16 // RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. CHAN3_RAW uint16 // RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. CHAN4_RAW uint16 // RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. CHAN5_RAW uint16 // RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. CHAN6_RAW uint16 // RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. CHAN7_RAW uint16 // RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. CHAN8_RAW uint16 // RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE RC_CHANNELS_OVERRIDE
MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70
MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18
MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124
func NewRcChannelsOverride ¶
func NewRcChannelsOverride(CHAN1_RAW uint16, CHAN2_RAW uint16, CHAN3_RAW uint16, CHAN4_RAW uint16, CHAN5_RAW uint16, CHAN6_RAW uint16, CHAN7_RAW uint16, CHAN8_RAW uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *RcChannelsOverride
NewRcChannelsOverride returns a new RcChannelsOverride
func (*RcChannelsOverride) Crc ¶
func (*RcChannelsOverride) Crc() uint8
Crc returns the RcChannelsOverride Message CRC
func (*RcChannelsOverride) Decode ¶
func (m *RcChannelsOverride) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the RcChannelsOverride
func (*RcChannelsOverride) Id ¶
func (*RcChannelsOverride) Id() uint8
Id returns the RcChannelsOverride Message ID
func (*RcChannelsOverride) Len ¶
func (*RcChannelsOverride) Len() uint8
Len returns the RcChannelsOverride Message Length
func (*RcChannelsOverride) Pack ¶
func (m *RcChannelsOverride) Pack() []byte
Pack returns a packed byte array which represents a RcChannelsOverride payload
type RcChannelsRaw ¶
type RcChannelsRaw struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) CHAN1_RAW uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN2_RAW uint16 // RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN3_RAW uint16 // RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN4_RAW uint16 // RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN5_RAW uint16 // RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN6_RAW uint16 // RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN7_RAW uint16 // RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. CHAN8_RAW uint16 // RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. PORT uint8 // Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. RSSI uint8 // Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. }
MESSAGE RC_CHANNELS_RAW
MAVLINK_MSG_ID_RC_CHANNELS_RAW 35
MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22
MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244
func NewRcChannelsRaw ¶
func NewRcChannelsRaw(TIME_BOOT_MS uint32, CHAN1_RAW uint16, CHAN2_RAW uint16, CHAN3_RAW uint16, CHAN4_RAW uint16, CHAN5_RAW uint16, CHAN6_RAW uint16, CHAN7_RAW uint16, CHAN8_RAW uint16, PORT uint8, RSSI uint8) *RcChannelsRaw
NewRcChannelsRaw returns a new RcChannelsRaw
func (*RcChannelsRaw) Crc ¶
func (*RcChannelsRaw) Crc() uint8
Crc returns the RcChannelsRaw Message CRC
func (*RcChannelsRaw) Decode ¶
func (m *RcChannelsRaw) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the RcChannelsRaw
func (*RcChannelsRaw) Len ¶
func (*RcChannelsRaw) Len() uint8
Len returns the RcChannelsRaw Message Length
func (*RcChannelsRaw) Pack ¶
func (m *RcChannelsRaw) Pack() []byte
Pack returns a packed byte array which represents a RcChannelsRaw payload
type RcChannelsScaled ¶
type RcChannelsScaled struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) CHAN1_SCALED int16 // RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. CHAN2_SCALED int16 // RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. CHAN3_SCALED int16 // RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. CHAN4_SCALED int16 // RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. CHAN5_SCALED int16 // RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. CHAN6_SCALED int16 // RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. CHAN7_SCALED int16 // RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. CHAN8_SCALED int16 // RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. PORT uint8 // Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. RSSI uint8 // Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. }
MESSAGE RC_CHANNELS_SCALED
MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34
MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22
MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237
func NewRcChannelsScaled ¶
func NewRcChannelsScaled(TIME_BOOT_MS uint32, CHAN1_SCALED int16, CHAN2_SCALED int16, CHAN3_SCALED int16, CHAN4_SCALED int16, CHAN5_SCALED int16, CHAN6_SCALED int16, CHAN7_SCALED int16, CHAN8_SCALED int16, PORT uint8, RSSI uint8) *RcChannelsScaled
NewRcChannelsScaled returns a new RcChannelsScaled
func (*RcChannelsScaled) Crc ¶
func (*RcChannelsScaled) Crc() uint8
Crc returns the RcChannelsScaled Message CRC
func (*RcChannelsScaled) Decode ¶
func (m *RcChannelsScaled) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the RcChannelsScaled
func (*RcChannelsScaled) Id ¶
func (*RcChannelsScaled) Id() uint8
Id returns the RcChannelsScaled Message ID
func (*RcChannelsScaled) Len ¶
func (*RcChannelsScaled) Len() uint8
Len returns the RcChannelsScaled Message Length
func (*RcChannelsScaled) Pack ¶
func (m *RcChannelsScaled) Pack() []byte
Pack returns a packed byte array which represents a RcChannelsScaled payload
type RequestDataStream ¶
type RequestDataStream struct { REQ_MESSAGE_RATE uint16 // The requested interval between two messages of this type TARGET_SYSTEM uint8 // The target requested to send the message stream. TARGET_COMPONENT uint8 // The target requested to send the message stream. REQ_STREAM_ID uint8 // The ID of the requested data stream START_STOP uint8 // 1 to start sending, 0 to stop sending. }
MESSAGE REQUEST_DATA_STREAM
MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66
MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6
MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148
func NewRequestDataStream ¶
func NewRequestDataStream(REQ_MESSAGE_RATE uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, REQ_STREAM_ID uint8, START_STOP uint8) *RequestDataStream
NewRequestDataStream returns a new RequestDataStream
func (*RequestDataStream) Crc ¶
func (*RequestDataStream) Crc() uint8
Crc returns the RequestDataStream Message CRC
func (*RequestDataStream) Decode ¶
func (m *RequestDataStream) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the RequestDataStream
func (*RequestDataStream) Id ¶
func (*RequestDataStream) Id() uint8
Id returns the RequestDataStream Message ID
func (*RequestDataStream) Len ¶
func (*RequestDataStream) Len() uint8
Len returns the RequestDataStream Message Length
func (*RequestDataStream) Pack ¶
func (m *RequestDataStream) Pack() []byte
Pack returns a packed byte array which represents a RequestDataStream payload
type RollPitchYawRatesThrustSetpoint ¶
type RollPitchYawRatesThrustSetpoint struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot ROLL_RATE float32 // Desired roll rate in radians per second PITCH_RATE float32 // Desired pitch rate in radians per second YAW_RATE float32 // Desired yaw rate in radians per second THRUST float32 // Collective thrust, normalized to 0 .. 1 }
MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT
MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT 80
MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN 20
MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC 127
func NewRollPitchYawRatesThrustSetpoint ¶
func NewRollPitchYawRatesThrustSetpoint(TIME_BOOT_MS uint32, ROLL_RATE float32, PITCH_RATE float32, YAW_RATE float32, THRUST float32) *RollPitchYawRatesThrustSetpoint
NewRollPitchYawRatesThrustSetpoint returns a new RollPitchYawRatesThrustSetpoint
func (*RollPitchYawRatesThrustSetpoint) Crc ¶
func (*RollPitchYawRatesThrustSetpoint) Crc() uint8
Crc returns the RollPitchYawRatesThrustSetpoint Message CRC
func (*RollPitchYawRatesThrustSetpoint) Decode ¶
func (m *RollPitchYawRatesThrustSetpoint) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the RollPitchYawRatesThrustSetpoint
func (*RollPitchYawRatesThrustSetpoint) Id ¶
func (*RollPitchYawRatesThrustSetpoint) Id() uint8
Id returns the RollPitchYawRatesThrustSetpoint Message ID
func (*RollPitchYawRatesThrustSetpoint) Len ¶
func (*RollPitchYawRatesThrustSetpoint) Len() uint8
Len returns the RollPitchYawRatesThrustSetpoint Message Length
func (*RollPitchYawRatesThrustSetpoint) Pack ¶
func (m *RollPitchYawRatesThrustSetpoint) Pack() []byte
Pack returns a packed byte array which represents a RollPitchYawRatesThrustSetpoint payload
type RollPitchYawSpeedThrustSetpoint ¶
type RollPitchYawSpeedThrustSetpoint struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot ROLL_SPEED float32 // Desired roll angular speed in rad/s PITCH_SPEED float32 // Desired pitch angular speed in rad/s YAW_SPEED float32 // Desired yaw angular speed in rad/s THRUST float32 // Collective thrust, normalized to 0 .. 1 }
MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT
MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 59
MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN 20
MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC 238
func NewRollPitchYawSpeedThrustSetpoint ¶
func NewRollPitchYawSpeedThrustSetpoint(TIME_BOOT_MS uint32, ROLL_SPEED float32, PITCH_SPEED float32, YAW_SPEED float32, THRUST float32) *RollPitchYawSpeedThrustSetpoint
NewRollPitchYawSpeedThrustSetpoint returns a new RollPitchYawSpeedThrustSetpoint
func (*RollPitchYawSpeedThrustSetpoint) Crc ¶
func (*RollPitchYawSpeedThrustSetpoint) Crc() uint8
Crc returns the RollPitchYawSpeedThrustSetpoint Message CRC
func (*RollPitchYawSpeedThrustSetpoint) Decode ¶
func (m *RollPitchYawSpeedThrustSetpoint) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the RollPitchYawSpeedThrustSetpoint
func (*RollPitchYawSpeedThrustSetpoint) Id ¶
func (*RollPitchYawSpeedThrustSetpoint) Id() uint8
Id returns the RollPitchYawSpeedThrustSetpoint Message ID
func (*RollPitchYawSpeedThrustSetpoint) Len ¶
func (*RollPitchYawSpeedThrustSetpoint) Len() uint8
Len returns the RollPitchYawSpeedThrustSetpoint Message Length
func (*RollPitchYawSpeedThrustSetpoint) Pack ¶
func (m *RollPitchYawSpeedThrustSetpoint) Pack() []byte
Pack returns a packed byte array which represents a RollPitchYawSpeedThrustSetpoint payload
type RollPitchYawThrustSetpoint ¶
type RollPitchYawThrustSetpoint struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot ROLL float32 // Desired roll angle in radians PITCH float32 // Desired pitch angle in radians YAW float32 // Desired yaw angle in radians THRUST float32 // Collective thrust, normalized to 0 .. 1 }
MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT
MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT 58
MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN 20
MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC 239
func NewRollPitchYawThrustSetpoint ¶
func NewRollPitchYawThrustSetpoint(TIME_BOOT_MS uint32, ROLL float32, PITCH float32, YAW float32, THRUST float32) *RollPitchYawThrustSetpoint
NewRollPitchYawThrustSetpoint returns a new RollPitchYawThrustSetpoint
func (*RollPitchYawThrustSetpoint) Crc ¶
func (*RollPitchYawThrustSetpoint) Crc() uint8
Crc returns the RollPitchYawThrustSetpoint Message CRC
func (*RollPitchYawThrustSetpoint) Decode ¶
func (m *RollPitchYawThrustSetpoint) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the RollPitchYawThrustSetpoint
func (*RollPitchYawThrustSetpoint) Id ¶
func (*RollPitchYawThrustSetpoint) Id() uint8
Id returns the RollPitchYawThrustSetpoint Message ID
func (*RollPitchYawThrustSetpoint) Len ¶
func (*RollPitchYawThrustSetpoint) Len() uint8
Len returns the RollPitchYawThrustSetpoint Message Length
func (*RollPitchYawThrustSetpoint) Pack ¶
func (m *RollPitchYawThrustSetpoint) Pack() []byte
Pack returns a packed byte array which represents a RollPitchYawThrustSetpoint payload
type SafetyAllowedArea ¶
type SafetyAllowedArea struct { P1X float32 // x position 1 / Latitude 1 P1Y float32 // y position 1 / Longitude 1 P1Z float32 // z position 1 / Altitude 1 P2X float32 // x position 2 / Latitude 2 P2Y float32 // y position 2 / Longitude 2 P2Z float32 // z position 2 / Altitude 2 FRAME uint8 // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. }
MESSAGE SAFETY_ALLOWED_AREA
MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55
MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25
MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3
func NewSafetyAllowedArea ¶
func NewSafetyAllowedArea(P1X float32, P1Y float32, P1Z float32, P2X float32, P2Y float32, P2Z float32, FRAME uint8) *SafetyAllowedArea
NewSafetyAllowedArea returns a new SafetyAllowedArea
func (*SafetyAllowedArea) Crc ¶
func (*SafetyAllowedArea) Crc() uint8
Crc returns the SafetyAllowedArea Message CRC
func (*SafetyAllowedArea) Decode ¶
func (m *SafetyAllowedArea) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SafetyAllowedArea
func (*SafetyAllowedArea) Id ¶
func (*SafetyAllowedArea) Id() uint8
Id returns the SafetyAllowedArea Message ID
func (*SafetyAllowedArea) Len ¶
func (*SafetyAllowedArea) Len() uint8
Len returns the SafetyAllowedArea Message Length
func (*SafetyAllowedArea) Pack ¶
func (m *SafetyAllowedArea) Pack() []byte
Pack returns a packed byte array which represents a SafetyAllowedArea payload
type SafetySetAllowedArea ¶
type SafetySetAllowedArea struct { P1X float32 // x position 1 / Latitude 1 P1Y float32 // y position 1 / Longitude 1 P1Z float32 // z position 1 / Altitude 1 P2X float32 // x position 2 / Latitude 2 P2Y float32 // y position 2 / Longitude 2 P2Z float32 // z position 2 / Altitude 2 TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID FRAME uint8 // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. }
MESSAGE SAFETY_SET_ALLOWED_AREA
MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54
MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27
MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15
func NewSafetySetAllowedArea ¶
func NewSafetySetAllowedArea(P1X float32, P1Y float32, P1Z float32, P2X float32, P2Y float32, P2Z float32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, FRAME uint8) *SafetySetAllowedArea
NewSafetySetAllowedArea returns a new SafetySetAllowedArea
func (*SafetySetAllowedArea) Crc ¶
func (*SafetySetAllowedArea) Crc() uint8
Crc returns the SafetySetAllowedArea Message CRC
func (*SafetySetAllowedArea) Decode ¶
func (m *SafetySetAllowedArea) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SafetySetAllowedArea
func (*SafetySetAllowedArea) Id ¶
func (*SafetySetAllowedArea) Id() uint8
Id returns the SafetySetAllowedArea Message ID
func (*SafetySetAllowedArea) Len ¶
func (*SafetySetAllowedArea) Len() uint8
Len returns the SafetySetAllowedArea Message Length
func (*SafetySetAllowedArea) Pack ¶
func (m *SafetySetAllowedArea) Pack() []byte
Pack returns a packed byte array which represents a SafetySetAllowedArea payload
type ScaledImu ¶
type ScaledImu struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) XACC int16 // X acceleration (mg) YACC int16 // Y acceleration (mg) ZACC int16 // Z acceleration (mg) XGYRO int16 // Angular speed around X axis (millirad /sec) YGYRO int16 // Angular speed around Y axis (millirad /sec) ZGYRO int16 // Angular speed around Z axis (millirad /sec) XMAG int16 // X Magnetic field (milli tesla) YMAG int16 // Y Magnetic field (milli tesla) ZMAG int16 // Z Magnetic field (milli tesla) }
MESSAGE SCALED_IMU
MAVLINK_MSG_ID_SCALED_IMU 26
MAVLINK_MSG_ID_SCALED_IMU_LEN 22
MAVLINK_MSG_ID_SCALED_IMU_CRC 170
func NewScaledImu ¶
func NewScaledImu(TIME_BOOT_MS uint32, XACC int16, YACC int16, ZACC int16, XGYRO int16, YGYRO int16, ZGYRO int16, XMAG int16, YMAG int16, ZMAG int16) *ScaledImu
NewScaledImu returns a new ScaledImu
type ScaledImu2 ¶
type ScaledImu2 struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) XACC int16 // X acceleration (mg) YACC int16 // Y acceleration (mg) ZACC int16 // Z acceleration (mg) XGYRO int16 // Angular speed around X axis (millirad /sec) YGYRO int16 // Angular speed around Y axis (millirad /sec) ZGYRO int16 // Angular speed around Z axis (millirad /sec) XMAG int16 // X Magnetic field (milli tesla) YMAG int16 // Y Magnetic field (milli tesla) ZMAG int16 // Z Magnetic field (milli tesla) }
MESSAGE SCALED_IMU2
MAVLINK_MSG_ID_SCALED_IMU2 116
MAVLINK_MSG_ID_SCALED_IMU2_LEN 22
MAVLINK_MSG_ID_SCALED_IMU2_CRC 76
func NewScaledImu2 ¶
func NewScaledImu2(TIME_BOOT_MS uint32, XACC int16, YACC int16, ZACC int16, XGYRO int16, YGYRO int16, ZGYRO int16, XMAG int16, YMAG int16, ZMAG int16) *ScaledImu2
NewScaledImu2 returns a new ScaledImu2
func (*ScaledImu2) Decode ¶
func (m *ScaledImu2) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the ScaledImu2
func (*ScaledImu2) Pack ¶
func (m *ScaledImu2) Pack() []byte
Pack returns a packed byte array which represents a ScaledImu2 payload
type ScaledPressure ¶
type ScaledPressure struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) PRESS_ABS float32 // Absolute pressure (hectopascal) PRESS_DIFF float32 // Differential pressure 1 (hectopascal) TEMPERATURE int16 // Temperature measurement (0.01 degrees celsius) }
MESSAGE SCALED_PRESSURE
MAVLINK_MSG_ID_SCALED_PRESSURE 29
MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14
MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115
func NewScaledPressure ¶
func NewScaledPressure(TIME_BOOT_MS uint32, PRESS_ABS float32, PRESS_DIFF float32, TEMPERATURE int16) *ScaledPressure
NewScaledPressure returns a new ScaledPressure
func (*ScaledPressure) Crc ¶
func (*ScaledPressure) Crc() uint8
Crc returns the ScaledPressure Message CRC
func (*ScaledPressure) Decode ¶
func (m *ScaledPressure) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the ScaledPressure
func (*ScaledPressure) Id ¶
func (*ScaledPressure) Id() uint8
Id returns the ScaledPressure Message ID
func (*ScaledPressure) Len ¶
func (*ScaledPressure) Len() uint8
Len returns the ScaledPressure Message Length
func (*ScaledPressure) Pack ¶
func (m *ScaledPressure) Pack() []byte
Pack returns a packed byte array which represents a ScaledPressure payload
type SerialControl ¶
type SerialControl struct { BAUDRATE uint32 // Baudrate of transfer. Zero means no change. TIMEOUT uint16 // Timeout for reply data in milliseconds DEVICE uint8 // See SERIAL_CONTROL_DEV enum FLAGS uint8 // See SERIAL_CONTROL_FLAG enum COUNT uint8 // how many bytes in this transfer DATA [70]uint8 // serial data }
MESSAGE SERIAL_CONTROL
MAVLINK_MSG_ID_SERIAL_CONTROL 126
MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79
MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220
func NewSerialControl ¶
func NewSerialControl(BAUDRATE uint32, TIMEOUT uint16, DEVICE uint8, FLAGS uint8, COUNT uint8, DATA [70]uint8) *SerialControl
NewSerialControl returns a new SerialControl
func (*SerialControl) Crc ¶
func (*SerialControl) Crc() uint8
Crc returns the SerialControl Message CRC
func (*SerialControl) Decode ¶
func (m *SerialControl) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SerialControl
func (*SerialControl) Len ¶
func (*SerialControl) Len() uint8
Len returns the SerialControl Message Length
func (*SerialControl) Pack ¶
func (m *SerialControl) Pack() []byte
Pack returns a packed byte array which represents a SerialControl payload
type ServoOutputRaw ¶
type ServoOutputRaw struct { TIME_USEC uint32 // Timestamp (microseconds since system boot) SERVO1_RAW uint16 // Servo output 1 value, in microseconds SERVO2_RAW uint16 // Servo output 2 value, in microseconds SERVO3_RAW uint16 // Servo output 3 value, in microseconds SERVO4_RAW uint16 // Servo output 4 value, in microseconds SERVO5_RAW uint16 // Servo output 5 value, in microseconds SERVO6_RAW uint16 // Servo output 6 value, in microseconds SERVO7_RAW uint16 // Servo output 7 value, in microseconds SERVO8_RAW uint16 // Servo output 8 value, in microseconds PORT uint8 // Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. }
MESSAGE SERVO_OUTPUT_RAW
MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36
MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21
MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC 222
func NewServoOutputRaw ¶
func NewServoOutputRaw(TIME_USEC uint32, SERVO1_RAW uint16, SERVO2_RAW uint16, SERVO3_RAW uint16, SERVO4_RAW uint16, SERVO5_RAW uint16, SERVO6_RAW uint16, SERVO7_RAW uint16, SERVO8_RAW uint16, PORT uint8) *ServoOutputRaw
NewServoOutputRaw returns a new ServoOutputRaw
func (*ServoOutputRaw) Crc ¶
func (*ServoOutputRaw) Crc() uint8
Crc returns the ServoOutputRaw Message CRC
func (*ServoOutputRaw) Decode ¶
func (m *ServoOutputRaw) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the ServoOutputRaw
func (*ServoOutputRaw) Id ¶
func (*ServoOutputRaw) Id() uint8
Id returns the ServoOutputRaw Message ID
func (*ServoOutputRaw) Len ¶
func (*ServoOutputRaw) Len() uint8
Len returns the ServoOutputRaw Message Length
func (*ServoOutputRaw) Pack ¶
func (m *ServoOutputRaw) Pack() []byte
Pack returns a packed byte array which represents a ServoOutputRaw payload
type SetGlobalPositionSetpointInt ¶
type SetGlobalPositionSetpointInt struct { LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 LONGITUDE int32 // Longitude (WGS84), in degrees * 1E7 ALTITUDE int32 // Altitude (WGS84), in meters * 1000 (positive for up) YAW int16 // Desired yaw angle in degrees * 100 COORDINATE_FRAME uint8 // Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT }
MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT
MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT 53
MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN 15
MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC 33
func NewSetGlobalPositionSetpointInt ¶
func NewSetGlobalPositionSetpointInt(LATITUDE int32, LONGITUDE int32, ALTITUDE int32, YAW int16, COORDINATE_FRAME uint8) *SetGlobalPositionSetpointInt
NewSetGlobalPositionSetpointInt returns a new SetGlobalPositionSetpointInt
func (*SetGlobalPositionSetpointInt) Crc ¶
func (*SetGlobalPositionSetpointInt) Crc() uint8
Crc returns the SetGlobalPositionSetpointInt Message CRC
func (*SetGlobalPositionSetpointInt) Decode ¶
func (m *SetGlobalPositionSetpointInt) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SetGlobalPositionSetpointInt
func (*SetGlobalPositionSetpointInt) Id ¶
func (*SetGlobalPositionSetpointInt) Id() uint8
Id returns the SetGlobalPositionSetpointInt Message ID
func (*SetGlobalPositionSetpointInt) Len ¶
func (*SetGlobalPositionSetpointInt) Len() uint8
Len returns the SetGlobalPositionSetpointInt Message Length
func (*SetGlobalPositionSetpointInt) Pack ¶
func (m *SetGlobalPositionSetpointInt) Pack() []byte
Pack returns a packed byte array which represents a SetGlobalPositionSetpointInt payload
type SetGpsGlobalOrigin ¶
type SetGpsGlobalOrigin struct { LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 LONGITUDE int32 // Longitude (WGS84, in degrees * 1E7 ALTITUDE int32 // Altitude (WGS84), in meters * 1000 (positive for up) TARGET_SYSTEM uint8 // System ID }
MESSAGE SET_GPS_GLOBAL_ORIGIN
MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48
MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13
MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC 41
func NewSetGpsGlobalOrigin ¶
func NewSetGpsGlobalOrigin(LATITUDE int32, LONGITUDE int32, ALTITUDE int32, TARGET_SYSTEM uint8) *SetGpsGlobalOrigin
NewSetGpsGlobalOrigin returns a new SetGpsGlobalOrigin
func (*SetGpsGlobalOrigin) Crc ¶
func (*SetGpsGlobalOrigin) Crc() uint8
Crc returns the SetGpsGlobalOrigin Message CRC
func (*SetGpsGlobalOrigin) Decode ¶
func (m *SetGpsGlobalOrigin) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SetGpsGlobalOrigin
func (*SetGpsGlobalOrigin) Id ¶
func (*SetGpsGlobalOrigin) Id() uint8
Id returns the SetGpsGlobalOrigin Message ID
func (*SetGpsGlobalOrigin) Len ¶
func (*SetGpsGlobalOrigin) Len() uint8
Len returns the SetGpsGlobalOrigin Message Length
func (*SetGpsGlobalOrigin) Pack ¶
func (m *SetGpsGlobalOrigin) Pack() []byte
Pack returns a packed byte array which represents a SetGpsGlobalOrigin payload
type SetLocalPositionSetpoint ¶
type SetLocalPositionSetpoint struct { X float32 // x position Y float32 // y position Z float32 // z position YAW float32 // Desired yaw angle TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID COORDINATE_FRAME uint8 // Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU }
MESSAGE SET_LOCAL_POSITION_SETPOINT
MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT 50
MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN 19
MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC 214
func NewSetLocalPositionSetpoint ¶
func NewSetLocalPositionSetpoint(X float32, Y float32, Z float32, YAW float32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, COORDINATE_FRAME uint8) *SetLocalPositionSetpoint
NewSetLocalPositionSetpoint returns a new SetLocalPositionSetpoint
func (*SetLocalPositionSetpoint) Crc ¶
func (*SetLocalPositionSetpoint) Crc() uint8
Crc returns the SetLocalPositionSetpoint Message CRC
func (*SetLocalPositionSetpoint) Decode ¶
func (m *SetLocalPositionSetpoint) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SetLocalPositionSetpoint
func (*SetLocalPositionSetpoint) Id ¶
func (*SetLocalPositionSetpoint) Id() uint8
Id returns the SetLocalPositionSetpoint Message ID
func (*SetLocalPositionSetpoint) Len ¶
func (*SetLocalPositionSetpoint) Len() uint8
Len returns the SetLocalPositionSetpoint Message Length
func (*SetLocalPositionSetpoint) Pack ¶
func (m *SetLocalPositionSetpoint) Pack() []byte
Pack returns a packed byte array which represents a SetLocalPositionSetpoint payload
type SetMode ¶
type SetMode struct { CUSTOM_MODE uint32 // The new autopilot-specific mode. This field can be ignored by an autopilot. TARGET_SYSTEM uint8 // The system setting the mode BASE_MODE uint8 // The new base mode }
MESSAGE SET_MODE
MAVLINK_MSG_ID_SET_MODE 11
MAVLINK_MSG_ID_SET_MODE_LEN 6
MAVLINK_MSG_ID_SET_MODE_CRC 89
func NewSetMode ¶
NewSetMode returns a new SetMode
type SetQuadMotorsSetpoint ¶
type SetQuadMotorsSetpoint struct { MOTOR_FRONT_NW uint16 // Front motor in + configuration, front left motor in x configuration MOTOR_RIGHT_NE uint16 // Right motor in + configuration, front right motor in x configuration MOTOR_BACK_SE uint16 // Back motor in + configuration, back right motor in x configuration MOTOR_LEFT_SW uint16 // Left motor in + configuration, back left motor in x configuration TARGET_SYSTEM uint8 // System ID of the system that should set these motor commands }
MESSAGE SET_QUAD_MOTORS_SETPOINT
MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT 60
MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN 9
MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC 30
func NewSetQuadMotorsSetpoint ¶
func NewSetQuadMotorsSetpoint(MOTOR_FRONT_NW uint16, MOTOR_RIGHT_NE uint16, MOTOR_BACK_SE uint16, MOTOR_LEFT_SW uint16, TARGET_SYSTEM uint8) *SetQuadMotorsSetpoint
NewSetQuadMotorsSetpoint returns a new SetQuadMotorsSetpoint
func (*SetQuadMotorsSetpoint) Crc ¶
func (*SetQuadMotorsSetpoint) Crc() uint8
Crc returns the SetQuadMotorsSetpoint Message CRC
func (*SetQuadMotorsSetpoint) Decode ¶
func (m *SetQuadMotorsSetpoint) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SetQuadMotorsSetpoint
func (*SetQuadMotorsSetpoint) Id ¶
func (*SetQuadMotorsSetpoint) Id() uint8
Id returns the SetQuadMotorsSetpoint Message ID
func (*SetQuadMotorsSetpoint) Len ¶
func (*SetQuadMotorsSetpoint) Len() uint8
Len returns the SetQuadMotorsSetpoint Message Length
func (*SetQuadMotorsSetpoint) Pack ¶
func (m *SetQuadMotorsSetpoint) Pack() []byte
Pack returns a packed byte array which represents a SetQuadMotorsSetpoint payload
type SetQuadSwarmLedRollPitchYawThrust ¶
type SetQuadSwarmLedRollPitchYawThrust struct { ROLL [4]int16 // Desired roll angle in radians +-PI (+-INT16_MAX) PITCH [4]int16 // Desired pitch angle in radians +-PI (+-INT16_MAX) YAW [4]int16 // Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) THRUST [4]uint16 // Collective thrust, scaled to uint16 (0..UINT16_MAX) GROUP uint8 // ID of the quadrotor group (0 - 255, up to 256 groups supported) MODE uint8 // ID of the flight mode (0 - 255, up to 256 modes supported) LED_RED [4]uint8 // RGB red channel (0-255) LED_BLUE [4]uint8 // RGB green channel (0-255) LED_GREEN [4]uint8 // RGB blue channel (0-255) }
MESSAGE SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST
MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST 63
MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN 46
MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC 130
func NewSetQuadSwarmLedRollPitchYawThrust ¶
func NewSetQuadSwarmLedRollPitchYawThrust(ROLL [4]int16, PITCH [4]int16, YAW [4]int16, THRUST [4]uint16, GROUP uint8, MODE uint8, LED_RED [4]uint8, LED_BLUE [4]uint8, LED_GREEN [4]uint8) *SetQuadSwarmLedRollPitchYawThrust
NewSetQuadSwarmLedRollPitchYawThrust returns a new SetQuadSwarmLedRollPitchYawThrust
func (*SetQuadSwarmLedRollPitchYawThrust) Crc ¶
func (*SetQuadSwarmLedRollPitchYawThrust) Crc() uint8
Crc returns the SetQuadSwarmLedRollPitchYawThrust Message CRC
func (*SetQuadSwarmLedRollPitchYawThrust) Decode ¶
func (m *SetQuadSwarmLedRollPitchYawThrust) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SetQuadSwarmLedRollPitchYawThrust
func (*SetQuadSwarmLedRollPitchYawThrust) Id ¶
func (*SetQuadSwarmLedRollPitchYawThrust) Id() uint8
Id returns the SetQuadSwarmLedRollPitchYawThrust Message ID
func (*SetQuadSwarmLedRollPitchYawThrust) Len ¶
func (*SetQuadSwarmLedRollPitchYawThrust) Len() uint8
Len returns the SetQuadSwarmLedRollPitchYawThrust Message Length
func (*SetQuadSwarmLedRollPitchYawThrust) Pack ¶
func (m *SetQuadSwarmLedRollPitchYawThrust) Pack() []byte
Pack returns a packed byte array which represents a SetQuadSwarmLedRollPitchYawThrust payload
type SetQuadSwarmRollPitchYawThrust ¶
type SetQuadSwarmRollPitchYawThrust struct { ROLL [4]int16 // Desired roll angle in radians +-PI (+-INT16_MAX) PITCH [4]int16 // Desired pitch angle in radians +-PI (+-INT16_MAX) YAW [4]int16 // Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) THRUST [4]uint16 // Collective thrust, scaled to uint16 (0..UINT16_MAX) GROUP uint8 // ID of the quadrotor group (0 - 255, up to 256 groups supported) MODE uint8 // ID of the flight mode (0 - 255, up to 256 modes supported) }
MESSAGE SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST
MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST 61
MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN 34
MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC 240
func NewSetQuadSwarmRollPitchYawThrust ¶
func NewSetQuadSwarmRollPitchYawThrust(ROLL [4]int16, PITCH [4]int16, YAW [4]int16, THRUST [4]uint16, GROUP uint8, MODE uint8) *SetQuadSwarmRollPitchYawThrust
NewSetQuadSwarmRollPitchYawThrust returns a new SetQuadSwarmRollPitchYawThrust
func (*SetQuadSwarmRollPitchYawThrust) Crc ¶
func (*SetQuadSwarmRollPitchYawThrust) Crc() uint8
Crc returns the SetQuadSwarmRollPitchYawThrust Message CRC
func (*SetQuadSwarmRollPitchYawThrust) Decode ¶
func (m *SetQuadSwarmRollPitchYawThrust) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SetQuadSwarmRollPitchYawThrust
func (*SetQuadSwarmRollPitchYawThrust) Id ¶
func (*SetQuadSwarmRollPitchYawThrust) Id() uint8
Id returns the SetQuadSwarmRollPitchYawThrust Message ID
func (*SetQuadSwarmRollPitchYawThrust) Len ¶
func (*SetQuadSwarmRollPitchYawThrust) Len() uint8
Len returns the SetQuadSwarmRollPitchYawThrust Message Length
func (*SetQuadSwarmRollPitchYawThrust) Pack ¶
func (m *SetQuadSwarmRollPitchYawThrust) Pack() []byte
Pack returns a packed byte array which represents a SetQuadSwarmRollPitchYawThrust payload
type SetRollPitchYawSpeedThrust ¶
type SetRollPitchYawSpeedThrust struct { ROLL_SPEED float32 // Desired roll angular speed in rad/s PITCH_SPEED float32 // Desired pitch angular speed in rad/s YAW_SPEED float32 // Desired yaw angular speed in rad/s THRUST float32 // Collective thrust, normalized to 0 .. 1 TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST 57
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN 18
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC 24
func NewSetRollPitchYawSpeedThrust ¶
func NewSetRollPitchYawSpeedThrust(ROLL_SPEED float32, PITCH_SPEED float32, YAW_SPEED float32, THRUST float32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *SetRollPitchYawSpeedThrust
NewSetRollPitchYawSpeedThrust returns a new SetRollPitchYawSpeedThrust
func (*SetRollPitchYawSpeedThrust) Crc ¶
func (*SetRollPitchYawSpeedThrust) Crc() uint8
Crc returns the SetRollPitchYawSpeedThrust Message CRC
func (*SetRollPitchYawSpeedThrust) Decode ¶
func (m *SetRollPitchYawSpeedThrust) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SetRollPitchYawSpeedThrust
func (*SetRollPitchYawSpeedThrust) Id ¶
func (*SetRollPitchYawSpeedThrust) Id() uint8
Id returns the SetRollPitchYawSpeedThrust Message ID
func (*SetRollPitchYawSpeedThrust) Len ¶
func (*SetRollPitchYawSpeedThrust) Len() uint8
Len returns the SetRollPitchYawSpeedThrust Message Length
func (*SetRollPitchYawSpeedThrust) Pack ¶
func (m *SetRollPitchYawSpeedThrust) Pack() []byte
Pack returns a packed byte array which represents a SetRollPitchYawSpeedThrust payload
type SetRollPitchYawThrust ¶
type SetRollPitchYawThrust struct { ROLL float32 // Desired roll angle in radians PITCH float32 // Desired pitch angle in radians YAW float32 // Desired yaw angle in radians THRUST float32 // Collective thrust, normalized to 0 .. 1 TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID }
MESSAGE SET_ROLL_PITCH_YAW_THRUST
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST 56
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN 18
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC 100
func NewSetRollPitchYawThrust ¶
func NewSetRollPitchYawThrust(ROLL float32, PITCH float32, YAW float32, THRUST float32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *SetRollPitchYawThrust
NewSetRollPitchYawThrust returns a new SetRollPitchYawThrust
func (*SetRollPitchYawThrust) Crc ¶
func (*SetRollPitchYawThrust) Crc() uint8
Crc returns the SetRollPitchYawThrust Message CRC
func (*SetRollPitchYawThrust) Decode ¶
func (m *SetRollPitchYawThrust) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SetRollPitchYawThrust
func (*SetRollPitchYawThrust) Id ¶
func (*SetRollPitchYawThrust) Id() uint8
Id returns the SetRollPitchYawThrust Message ID
func (*SetRollPitchYawThrust) Len ¶
func (*SetRollPitchYawThrust) Len() uint8
Len returns the SetRollPitchYawThrust Message Length
func (*SetRollPitchYawThrust) Pack ¶
func (m *SetRollPitchYawThrust) Pack() []byte
Pack returns a packed byte array which represents a SetRollPitchYawThrust payload
type Setpoint6Dof ¶
type Setpoint6Dof struct { TRANS_X float32 // Translational Component in x TRANS_Y float32 // Translational Component in y TRANS_Z float32 // Translational Component in z ROT_X float32 // Rotational Component in x ROT_Y float32 // Rotational Component in y ROT_Z float32 // Rotational Component in z TARGET_SYSTEM uint8 // System ID }
MESSAGE SETPOINT_6DOF
MAVLINK_MSG_ID_SETPOINT_6DOF 149
MAVLINK_MSG_ID_SETPOINT_6DOF_LEN 25
MAVLINK_MSG_ID_SETPOINT_6DOF_CRC 15
func NewSetpoint6Dof ¶
func NewSetpoint6Dof(TRANS_X float32, TRANS_Y float32, TRANS_Z float32, ROT_X float32, ROT_Y float32, ROT_Z float32, TARGET_SYSTEM uint8) *Setpoint6Dof
NewSetpoint6Dof returns a new Setpoint6Dof
func (*Setpoint6Dof) Crc ¶
func (*Setpoint6Dof) Crc() uint8
Crc returns the Setpoint6Dof Message CRC
func (*Setpoint6Dof) Decode ¶
func (m *Setpoint6Dof) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the Setpoint6Dof
func (*Setpoint6Dof) Len ¶
func (*Setpoint6Dof) Len() uint8
Len returns the Setpoint6Dof Message Length
func (*Setpoint6Dof) Pack ¶
func (m *Setpoint6Dof) Pack() []byte
Pack returns a packed byte array which represents a Setpoint6Dof payload
type Setpoint8Dof ¶
type Setpoint8Dof struct { VAL1 float32 // Value 1 VAL2 float32 // Value 2 VAL3 float32 // Value 3 VAL4 float32 // Value 4 VAL5 float32 // Value 5 VAL6 float32 // Value 6 VAL7 float32 // Value 7 VAL8 float32 // Value 8 TARGET_SYSTEM uint8 // System ID }
MESSAGE SETPOINT_8DOF
MAVLINK_MSG_ID_SETPOINT_8DOF 148
MAVLINK_MSG_ID_SETPOINT_8DOF_LEN 33
MAVLINK_MSG_ID_SETPOINT_8DOF_CRC 241
func NewSetpoint8Dof ¶
func NewSetpoint8Dof(VAL1 float32, VAL2 float32, VAL3 float32, VAL4 float32, VAL5 float32, VAL6 float32, VAL7 float32, VAL8 float32, TARGET_SYSTEM uint8) *Setpoint8Dof
NewSetpoint8Dof returns a new Setpoint8Dof
func (*Setpoint8Dof) Crc ¶
func (*Setpoint8Dof) Crc() uint8
Crc returns the Setpoint8Dof Message CRC
func (*Setpoint8Dof) Decode ¶
func (m *Setpoint8Dof) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the Setpoint8Dof
func (*Setpoint8Dof) Len ¶
func (*Setpoint8Dof) Len() uint8
Len returns the Setpoint8Dof Message Length
func (*Setpoint8Dof) Pack ¶
func (m *Setpoint8Dof) Pack() []byte
Pack returns a packed byte array which represents a Setpoint8Dof payload
type SimState ¶
type SimState struct { Q1 float32 // True attitude quaternion component 1, w (1 in null-rotation) Q2 float32 // True attitude quaternion component 2, x (0 in null-rotation) Q3 float32 // True attitude quaternion component 3, y (0 in null-rotation) Q4 float32 // True attitude quaternion component 4, z (0 in null-rotation) ROLL float32 // Attitude roll expressed as Euler angles, not recommended except for human-readable outputs PITCH float32 // Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs YAW float32 // Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs XACC float32 // X acceleration m/s/s YACC float32 // Y acceleration m/s/s ZACC float32 // Z acceleration m/s/s XGYRO float32 // Angular speed around X axis rad/s YGYRO float32 // Angular speed around Y axis rad/s ZGYRO float32 // Angular speed around Z axis rad/s LAT float32 // Latitude in degrees LON float32 // Longitude in degrees ALT float32 // Altitude in meters STD_DEV_HORZ float32 // Horizontal position standard deviation STD_DEV_VERT float32 // Vertical position standard deviation VN float32 // True velocity in m/s in NORTH direction in earth-fixed NED frame VE float32 // True velocity in m/s in EAST direction in earth-fixed NED frame VD float32 // True velocity in m/s in DOWN direction in earth-fixed NED frame }
MESSAGE SIM_STATE
MAVLINK_MSG_ID_SIM_STATE 108
MAVLINK_MSG_ID_SIM_STATE_LEN 84
MAVLINK_MSG_ID_SIM_STATE_CRC 32
func NewSimState ¶
func NewSimState(Q1 float32, Q2 float32, Q3 float32, Q4 float32, ROLL float32, PITCH float32, YAW float32, XACC float32, YACC float32, ZACC float32, XGYRO float32, YGYRO float32, ZGYRO float32, LAT float32, LON float32, ALT float32, STD_DEV_HORZ float32, STD_DEV_VERT float32, VN float32, VE float32, VD float32) *SimState
NewSimState returns a new SimState
type StateCorrection ¶
type StateCorrection struct { XERR float32 // x position error YERR float32 // y position error ZERR float32 // z position error ROLLERR float32 // roll error (radians) PITCHERR float32 // pitch error (radians) YAWERR float32 // yaw error (radians) VXERR float32 // x velocity VYERR float32 // y velocity VZERR float32 // z velocity }
MESSAGE STATE_CORRECTION
MAVLINK_MSG_ID_STATE_CORRECTION 64
MAVLINK_MSG_ID_STATE_CORRECTION_LEN 36
MAVLINK_MSG_ID_STATE_CORRECTION_CRC 130
func NewStateCorrection ¶
func NewStateCorrection(XERR float32, YERR float32, ZERR float32, ROLLERR float32, PITCHERR float32, YAWERR float32, VXERR float32, VYERR float32, VZERR float32) *StateCorrection
NewStateCorrection returns a new StateCorrection
func (*StateCorrection) Crc ¶
func (*StateCorrection) Crc() uint8
Crc returns the StateCorrection Message CRC
func (*StateCorrection) Decode ¶
func (m *StateCorrection) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the StateCorrection
func (*StateCorrection) Id ¶
func (*StateCorrection) Id() uint8
Id returns the StateCorrection Message ID
func (*StateCorrection) Len ¶
func (*StateCorrection) Len() uint8
Len returns the StateCorrection Message Length
func (*StateCorrection) Pack ¶
func (m *StateCorrection) Pack() []byte
Pack returns a packed byte array which represents a StateCorrection payload
type Statustext ¶
type Statustext struct { SEVERITY uint8 // Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. TEXT [50]uint8 // Status text message, without null termination character }
MESSAGE STATUSTEXT
MAVLINK_MSG_ID_STATUSTEXT 253
MAVLINK_MSG_ID_STATUSTEXT_LEN 51
MAVLINK_MSG_ID_STATUSTEXT_CRC 83
func NewStatustext ¶
func NewStatustext(SEVERITY uint8, TEXT [50]uint8) *Statustext
NewStatustext returns a new Statustext
func (*Statustext) Decode ¶
func (m *Statustext) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the Statustext
func (*Statustext) Pack ¶
func (m *Statustext) Pack() []byte
Pack returns a packed byte array which represents a Statustext payload
type SysStatus ¶
type SysStatus struct { ONBOARD_CONTROL_SENSORS_PRESENT uint32 // Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR ONBOARD_CONTROL_SENSORS_ENABLED uint32 // Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR ONBOARD_CONTROL_SENSORS_HEALTH uint32 // Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR LOAD uint16 // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 VOLTAGE_BATTERY uint16 // Battery voltage, in millivolts (1 = 1 millivolt) CURRENT_BATTERY int16 // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current DROP_RATE_COMM uint16 // Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) ERRORS_COMM uint16 // Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) ERRORS_COUNT1 uint16 // Autopilot-specific errors ERRORS_COUNT2 uint16 // Autopilot-specific errors ERRORS_COUNT3 uint16 // Autopilot-specific errors ERRORS_COUNT4 uint16 // Autopilot-specific errors BATTERY_REMAINING int8 // Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery }
MESSAGE SYS_STATUS
MAVLINK_MSG_ID_SYS_STATUS 1
MAVLINK_MSG_ID_SYS_STATUS_LEN 31
MAVLINK_MSG_ID_SYS_STATUS_CRC 124
func NewSysStatus ¶
func NewSysStatus(ONBOARD_CONTROL_SENSORS_PRESENT uint32, ONBOARD_CONTROL_SENSORS_ENABLED uint32, ONBOARD_CONTROL_SENSORS_HEALTH uint32, LOAD uint16, VOLTAGE_BATTERY uint16, CURRENT_BATTERY int16, DROP_RATE_COMM uint16, ERRORS_COMM uint16, ERRORS_COUNT1 uint16, ERRORS_COUNT2 uint16, ERRORS_COUNT3 uint16, ERRORS_COUNT4 uint16, BATTERY_REMAINING int8) *SysStatus
NewSysStatus returns a new SysStatus
type SystemTime ¶
type SystemTime struct { TIME_UNIX_USEC uint64 // Timestamp of the master clock in microseconds since UNIX epoch. TIME_BOOT_MS uint32 // Timestamp of the component clock since boot time in milliseconds. }
MESSAGE SYSTEM_TIME
MAVLINK_MSG_ID_SYSTEM_TIME 2
MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12
MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137
func NewSystemTime ¶
func NewSystemTime(TIME_UNIX_USEC uint64, TIME_BOOT_MS uint32) *SystemTime
NewSystemTime returns a new SystemTime
func (*SystemTime) Decode ¶
func (m *SystemTime) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the SystemTime
func (*SystemTime) Pack ¶
func (m *SystemTime) Pack() []byte
Pack returns a packed byte array which represents a SystemTime payload
type TerrainCheck ¶
type TerrainCheck struct { LAT int32 // Latitude (degrees *10^7) LON int32 // Longitude (degrees *10^7) }
MESSAGE TERRAIN_CHECK
MAVLINK_MSG_ID_TERRAIN_CHECK 135
MAVLINK_MSG_ID_TERRAIN_CHECK_LEN 8
MAVLINK_MSG_ID_TERRAIN_CHECK_CRC 203
func NewTerrainCheck ¶
func NewTerrainCheck(LAT int32, LON int32) *TerrainCheck
NewTerrainCheck returns a new TerrainCheck
func (*TerrainCheck) Crc ¶
func (*TerrainCheck) Crc() uint8
Crc returns the TerrainCheck Message CRC
func (*TerrainCheck) Decode ¶
func (m *TerrainCheck) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the TerrainCheck
func (*TerrainCheck) Len ¶
func (*TerrainCheck) Len() uint8
Len returns the TerrainCheck Message Length
func (*TerrainCheck) Pack ¶
func (m *TerrainCheck) Pack() []byte
Pack returns a packed byte array which represents a TerrainCheck payload
type TerrainData ¶
type TerrainData struct { LAT int32 // Latitude of SW corner of first grid (degrees *10^7) LON int32 // Longitude of SW corner of first grid (in degrees *10^7) GRID_SPACING uint16 // Grid spacing in meters DATA [16]int16 // Terrain data in meters AMSL GRIDBIT uint8 // bit within the terrain request mask }
MESSAGE TERRAIN_DATA
MAVLINK_MSG_ID_TERRAIN_DATA 134
MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43
MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229
func NewTerrainData ¶
func NewTerrainData(LAT int32, LON int32, GRID_SPACING uint16, DATA [16]int16, GRIDBIT uint8) *TerrainData
NewTerrainData returns a new TerrainData
func (*TerrainData) Decode ¶
func (m *TerrainData) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the TerrainData
func (*TerrainData) Len ¶
func (*TerrainData) Len() uint8
Len returns the TerrainData Message Length
func (*TerrainData) Pack ¶
func (m *TerrainData) Pack() []byte
Pack returns a packed byte array which represents a TerrainData payload
type TerrainReport ¶
type TerrainReport struct { LAT int32 // Latitude (degrees *10^7) LON int32 // Longitude (degrees *10^7) TERRAIN_HEIGHT float32 // Terrain height in meters AMSL CURRENT_HEIGHT float32 // Current vehicle height above lat/lon terrain height (meters) SPACING uint16 // grid spacing (zero if terrain at this location unavailable) PENDING uint16 // Number of 4x4 terrain blocks waiting to be received or read from disk LOADED uint16 // Number of 4x4 terrain blocks in memory }
MESSAGE TERRAIN_REPORT
MAVLINK_MSG_ID_TERRAIN_REPORT 136
MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22
MAVLINK_MSG_ID_TERRAIN_REPORT_CRC 1
func NewTerrainReport ¶
func NewTerrainReport(LAT int32, LON int32, TERRAIN_HEIGHT float32, CURRENT_HEIGHT float32, SPACING uint16, PENDING uint16, LOADED uint16) *TerrainReport
NewTerrainReport returns a new TerrainReport
func (*TerrainReport) Crc ¶
func (*TerrainReport) Crc() uint8
Crc returns the TerrainReport Message CRC
func (*TerrainReport) Decode ¶
func (m *TerrainReport) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the TerrainReport
func (*TerrainReport) Len ¶
func (*TerrainReport) Len() uint8
Len returns the TerrainReport Message Length
func (*TerrainReport) Pack ¶
func (m *TerrainReport) Pack() []byte
Pack returns a packed byte array which represents a TerrainReport payload
type TerrainRequest ¶
type TerrainRequest struct { MASK uint64 // Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) LAT int32 // Latitude of SW corner of first grid (degrees *10^7) LON int32 // Longitude of SW corner of first grid (in degrees *10^7) GRID_SPACING uint16 // Grid spacing in meters }
MESSAGE TERRAIN_REQUEST
MAVLINK_MSG_ID_TERRAIN_REQUEST 133
MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18
MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC 6
func NewTerrainRequest ¶
func NewTerrainRequest(MASK uint64, LAT int32, LON int32, GRID_SPACING uint16) *TerrainRequest
NewTerrainRequest returns a new TerrainRequest
func (*TerrainRequest) Crc ¶
func (*TerrainRequest) Crc() uint8
Crc returns the TerrainRequest Message CRC
func (*TerrainRequest) Decode ¶
func (m *TerrainRequest) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the TerrainRequest
func (*TerrainRequest) Id ¶
func (*TerrainRequest) Id() uint8
Id returns the TerrainRequest Message ID
func (*TerrainRequest) Len ¶
func (*TerrainRequest) Len() uint8
Len returns the TerrainRequest Message Length
func (*TerrainRequest) Pack ¶
func (m *TerrainRequest) Pack() []byte
Pack returns a packed byte array which represents a TerrainRequest payload
type VfrHud ¶
type VfrHud struct { AIRSPEED float32 // Current airspeed in m/s GROUNDSPEED float32 // Current ground speed in m/s ALT float32 // Current altitude (MSL), in meters CLIMB float32 // Current climb rate in meters/second HEADING int16 // Current heading in degrees, in compass units (0..360, 0=north) THROTTLE uint16 // Current throttle setting in integer percent, 0 to 100 }
MESSAGE VFR_HUD
MAVLINK_MSG_ID_VFR_HUD 74
MAVLINK_MSG_ID_VFR_HUD_LEN 20
MAVLINK_MSG_ID_VFR_HUD_CRC 20
func NewVfrHud ¶
func NewVfrHud(AIRSPEED float32, GROUNDSPEED float32, ALT float32, CLIMB float32, HEADING int16, THROTTLE uint16) *VfrHud
NewVfrHud returns a new VfrHud
type ViconPositionEstimate ¶
type ViconPositionEstimate struct { USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) X float32 // Global X position Y float32 // Global Y position Z float32 // Global Z position ROLL float32 // Roll angle in rad PITCH float32 // Pitch angle in rad YAW float32 // Yaw angle in rad }
MESSAGE VICON_POSITION_ESTIMATE
MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104
MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32
MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC 56
func NewViconPositionEstimate ¶
func NewViconPositionEstimate(USEC uint64, X float32, Y float32, Z float32, ROLL float32, PITCH float32, YAW float32) *ViconPositionEstimate
NewViconPositionEstimate returns a new ViconPositionEstimate
func (*ViconPositionEstimate) Crc ¶
func (*ViconPositionEstimate) Crc() uint8
Crc returns the ViconPositionEstimate Message CRC
func (*ViconPositionEstimate) Decode ¶
func (m *ViconPositionEstimate) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the ViconPositionEstimate
func (*ViconPositionEstimate) Id ¶
func (*ViconPositionEstimate) Id() uint8
Id returns the ViconPositionEstimate Message ID
func (*ViconPositionEstimate) Len ¶
func (*ViconPositionEstimate) Len() uint8
Len returns the ViconPositionEstimate Message Length
func (*ViconPositionEstimate) Pack ¶
func (m *ViconPositionEstimate) Pack() []byte
Pack returns a packed byte array which represents a ViconPositionEstimate payload
type VisionPositionEstimate ¶
type VisionPositionEstimate struct { USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) X float32 // Global X position Y float32 // Global Y position Z float32 // Global Z position ROLL float32 // Roll angle in rad PITCH float32 // Pitch angle in rad YAW float32 // Yaw angle in rad }
MESSAGE VISION_POSITION_ESTIMATE
MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102
MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32
MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC 158
func NewVisionPositionEstimate ¶
func NewVisionPositionEstimate(USEC uint64, X float32, Y float32, Z float32, ROLL float32, PITCH float32, YAW float32) *VisionPositionEstimate
NewVisionPositionEstimate returns a new VisionPositionEstimate
func (*VisionPositionEstimate) Crc ¶
func (*VisionPositionEstimate) Crc() uint8
Crc returns the VisionPositionEstimate Message CRC
func (*VisionPositionEstimate) Decode ¶
func (m *VisionPositionEstimate) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the VisionPositionEstimate
func (*VisionPositionEstimate) Id ¶
func (*VisionPositionEstimate) Id() uint8
Id returns the VisionPositionEstimate Message ID
func (*VisionPositionEstimate) Len ¶
func (*VisionPositionEstimate) Len() uint8
Len returns the VisionPositionEstimate Message Length
func (*VisionPositionEstimate) Pack ¶
func (m *VisionPositionEstimate) Pack() []byte
Pack returns a packed byte array which represents a VisionPositionEstimate payload
type VisionSpeedEstimate ¶
type VisionSpeedEstimate struct { USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) X float32 // Global X speed Y float32 // Global Y speed Z float32 // Global Z speed }
MESSAGE VISION_SPEED_ESTIMATE
MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103
MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20
MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208
func NewVisionSpeedEstimate ¶
func NewVisionSpeedEstimate(USEC uint64, X float32, Y float32, Z float32) *VisionSpeedEstimate
NewVisionSpeedEstimate returns a new VisionSpeedEstimate
func (*VisionSpeedEstimate) Crc ¶
func (*VisionSpeedEstimate) Crc() uint8
Crc returns the VisionSpeedEstimate Message CRC
func (*VisionSpeedEstimate) Decode ¶
func (m *VisionSpeedEstimate) Decode(buf []byte)
Decode accepts a packed byte array and populates the fields of the VisionSpeedEstimate
func (*VisionSpeedEstimate) Id ¶
func (*VisionSpeedEstimate) Id() uint8
Id returns the VisionSpeedEstimate Message ID
func (*VisionSpeedEstimate) Len ¶
func (*VisionSpeedEstimate) Len() uint8
Len returns the VisionSpeedEstimate Message Length
func (*VisionSpeedEstimate) Pack ¶
func (m *VisionSpeedEstimate) Pack() []byte
Pack returns a packed byte array which represents a VisionSpeedEstimate payload