gobot.io/x/gobot/v2@v2.1.0/platforms/mavlink/common/common.go (about) 1 package mavlink 2 3 // 4 // MAVLink comm protocol generated from common.xml 5 // http://qgroundcontrol.org/mavlink/ 6 // 7 import ( 8 "bytes" 9 "encoding/binary" 10 "fmt" 11 ) 12 13 var messages = map[uint8]MAVLinkMessage{ 14 0: &Heartbeat{}, 15 1: &SysStatus{}, 16 2: &SystemTime{}, 17 4: &Ping{}, 18 5: &ChangeOperatorControl{}, 19 6: &ChangeOperatorControlAck{}, 20 7: &AuthKey{}, 21 11: &SetMode{}, 22 20: &ParamRequestRead{}, 23 21: &ParamRequestList{}, 24 22: &ParamValue{}, 25 23: &ParamSet{}, 26 24: &GpsRawInt{}, 27 25: &GpsStatus{}, 28 26: &ScaledImu{}, 29 27: &RawImu{}, 30 28: &RawPressure{}, 31 29: &ScaledPressure{}, 32 30: &Attitude{}, 33 31: &AttitudeQuaternion{}, 34 32: &LocalPositionNed{}, 35 33: &GlobalPositionInt{}, 36 34: &RcChannelsScaled{}, 37 35: &RcChannelsRaw{}, 38 36: &ServoOutputRaw{}, 39 37: &MissionRequestPartialList{}, 40 38: &MissionWritePartialList{}, 41 39: &MissionItem{}, 42 40: &MissionRequest{}, 43 41: &MissionSetCurrent{}, 44 42: &MissionCurrent{}, 45 43: &MissionRequestList{}, 46 44: &MissionCount{}, 47 45: &MissionClearAll{}, 48 46: &MissionItemReached{}, 49 47: &MissionAck{}, 50 48: &SetGpsGlobalOrigin{}, 51 49: &GpsGlobalOrigin{}, 52 50: &SetLocalPositionSetpoint{}, 53 51: &LocalPositionSetpoint{}, 54 52: &GlobalPositionSetpointInt{}, 55 53: &SetGlobalPositionSetpointInt{}, 56 54: &SafetySetAllowedArea{}, 57 55: &SafetyAllowedArea{}, 58 56: &SetRollPitchYawThrust{}, 59 57: &SetRollPitchYawSpeedThrust{}, 60 58: &RollPitchYawThrustSetpoint{}, 61 59: &RollPitchYawSpeedThrustSetpoint{}, 62 60: &SetQuadMotorsSetpoint{}, 63 61: &SetQuadSwarmRollPitchYawThrust{}, 64 62: &NavControllerOutput{}, 65 63: &SetQuadSwarmLedRollPitchYawThrust{}, 66 64: &StateCorrection{}, 67 65: &RcChannels{}, 68 66: &RequestDataStream{}, 69 67: &DataStream{}, 70 69: &ManualControl{}, 71 70: &RcChannelsOverride{}, 72 74: &VfrHud{}, 73 76: &CommandLong{}, 74 77: &CommandAck{}, 75 80: &RollPitchYawRatesThrustSetpoint{}, 76 81: &ManualSetpoint{}, 77 82: &AttitudeSetpointExternal{}, 78 83: &LocalNedPositionSetpointExternal{}, 79 84: &GlobalPositionSetpointExternalInt{}, 80 89: &LocalPositionNedSystemGlobalOffset{}, 81 90: &HilState{}, 82 91: &HilControls{}, 83 92: &HilRcInputsRaw{}, 84 100: &OpticalFlow{}, 85 101: &GlobalVisionPositionEstimate{}, 86 102: &VisionPositionEstimate{}, 87 103: &VisionSpeedEstimate{}, 88 104: &ViconPositionEstimate{}, 89 105: &HighresImu{}, 90 106: &OmnidirectionalFlow{}, 91 107: &HilSensor{}, 92 108: &SimState{}, 93 109: &RadioStatus{}, 94 110: &FileTransferStart{}, 95 111: &FileTransferDirList{}, 96 112: &FileTransferRes{}, 97 113: &HilGps{}, 98 114: &HilOpticalFlow{}, 99 115: &HilStateQuaternion{}, 100 116: &ScaledImu2{}, 101 117: &LogRequestList{}, 102 118: &LogEntry{}, 103 119: &LogRequestData{}, 104 120: &LogData{}, 105 121: &LogErase{}, 106 122: &LogRequestEnd{}, 107 123: &GpsInjectData{}, 108 124: &Gps2Raw{}, 109 125: &PowerStatus{}, 110 126: &SerialControl{}, 111 127: &GpsRtk{}, 112 128: &Gps2Rtk{}, 113 130: &DataTransmissionHandshake{}, 114 131: &EncapsulatedData{}, 115 132: &DistanceSensor{}, 116 133: &TerrainRequest{}, 117 134: &TerrainData{}, 118 135: &TerrainCheck{}, 119 136: &TerrainReport{}, 120 147: &BatteryStatus{}, 121 148: &Setpoint8Dof{}, 122 149: &Setpoint6Dof{}, 123 249: &MemoryVect{}, 124 250: &DebugVect{}, 125 251: &NamedValueFloat{}, 126 252: &NamedValueInt{}, 127 253: &Statustext{}, 128 254: &Debug{}, 129 } 130 131 // NewMAVLinkMessage returns a new MAVLinkMessage or an error if it encounters an unknown Message ID 132 func NewMAVLinkMessage(msgid uint8, data []byte) (MAVLinkMessage, error) { 133 message := messages[msgid] 134 if message != nil { 135 message.Decode(data) 136 return message, nil 137 } 138 return nil, fmt.Errorf("Unknown Message ID: %v", msgid) 139 } 140 141 // 142 // MAV_AUTOPILOT 143 /*Micro air vehicle / autopilot classes. This identifies the individual model.*/ 144 // 145 const ( 146 MAV_AUTOPILOT_GENERIC = 0 // Generic autopilot, full support for everything | 147 MAV_AUTOPILOT_PIXHAWK = 1 // PIXHAWK autopilot, http://pixhawk.ethz.ch | 148 MAV_AUTOPILOT_SLUGS = 2 // SLUGS autopilot, http://slugsuav.soe.ucsc.edu | 149 MAV_AUTOPILOT_ARDUPILOTMEGA = 3 // ArduPilotMega / ArduCopter, http://diydrones.com | 150 MAV_AUTOPILOT_OPENPILOT = 4 // OpenPilot, http://openpilot.org | 151 MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5 // Generic autopilot only supporting simple waypoints | 152 MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6 // Generic autopilot supporting waypoints and other simple navigation commands | 153 MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7 // Generic autopilot supporting the full mission command set | 154 MAV_AUTOPILOT_INVALID = 8 // No valid autopilot, e.g. a GCS or other MAVLink component | 155 MAV_AUTOPILOT_PPZ = 9 // PPZ UAV - http://nongnu.org/paparazzi | 156 MAV_AUTOPILOT_UDB = 10 // UAV Dev Board | 157 MAV_AUTOPILOT_FP = 11 // FlexiPilot | 158 MAV_AUTOPILOT_PX4 = 12 // PX4 Autopilot - http://pixhawk.ethz.ch/px4/ | 159 MAV_AUTOPILOT_SMACCMPILOT = 13 // SMACCMPilot - http://smaccmpilot.org | 160 MAV_AUTOPILOT_AUTOQUAD = 14 // AutoQuad -- http://autoquad.org | 161 MAV_AUTOPILOT_ARMAZILA = 15 // Armazila -- http://armazila.com | 162 MAV_AUTOPILOT_AEROB = 16 // Aerob -- http://aerob.ru | 163 MAV_AUTOPILOT_ENUM_END = 17 // | 164 ) 165 166 // 167 // MAV_TYPE 168 /**/ 169 // 170 const ( 171 MAV_TYPE_GENERIC = 0 // Generic micro air vehicle. | 172 MAV_TYPE_FIXED_WING = 1 // Fixed wing aircraft. | 173 MAV_TYPE_QUADROTOR = 2 // Quadrotor | 174 MAV_TYPE_COAXIAL = 3 // Coaxial helicopter | 175 MAV_TYPE_HELICOPTER = 4 // Normal helicopter with tail rotor. | 176 MAV_TYPE_ANTENNA_TRACKER = 5 // Ground installation | 177 MAV_TYPE_GCS = 6 // Operator control unit / ground control station | 178 MAV_TYPE_AIRSHIP = 7 // Airship, controlled | 179 MAV_TYPE_FREE_BALLOON = 8 // Free balloon, uncontrolled | 180 MAV_TYPE_ROCKET = 9 // Rocket | 181 MAV_TYPE_GROUND_ROVER = 10 // Ground rover | 182 MAV_TYPE_SURFACE_BOAT = 11 // Surface vessel, boat, ship | 183 MAV_TYPE_SUBMARINE = 12 // Submarine | 184 MAV_TYPE_HEXAROTOR = 13 // Hexarotor | 185 MAV_TYPE_OCTOROTOR = 14 // Octorotor | 186 MAV_TYPE_TRICOPTER = 15 // Octorotor | 187 MAV_TYPE_FLAPPING_WING = 16 // Flapping wing | 188 MAV_TYPE_KITE = 17 // Flapping wing | 189 MAV_TYPE_ONBOARD_CONTROLLER = 18 // Onboard companion controller | 190 MAV_TYPE_ENUM_END = 19 // | 191 ) 192 193 // 194 // MAV_MODE_FLAG 195 /*These flags encode the MAV mode.*/ 196 // 197 const ( 198 MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 // 0b00000001 Reserved for future use. | 199 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. | 200 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. | 201 MAV_MODE_FLAG_GUIDED_ENABLED = 8 // 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | 202 MAV_MODE_FLAG_STABILIZE_ENABLED = 16 // 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | 203 MAV_MODE_FLAG_HIL_ENABLED = 32 // 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | 204 MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 // 0b01000000 remote control input is enabled. | 205 MAV_MODE_FLAG_SAFETY_ARMED = 128 // 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | 206 MAV_MODE_FLAG_ENUM_END = 129 // | 207 ) 208 209 // 210 // MAV_MODE_FLAG_DECODE_POSITION 211 /*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.*/ 212 // 213 const ( 214 MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1 // Eighth bit: 00000001 | 215 MAV_MODE_FLAG_DECODE_POSITION_TEST = 2 // Seventh bit: 00000010 | 216 MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4 // Sixt bit: 00000100 | 217 MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8 // Fifth bit: 00001000 | 218 MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16 // Fourth bit: 00010000 | 219 MAV_MODE_FLAG_DECODE_POSITION_HIL = 32 // Third bit: 00100000 | 220 MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64 // Second bit: 01000000 | 221 MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128 // First bit: 10000000 | 222 MAV_MODE_FLAG_DECODE_POSITION_ENUM_END = 129 // | 223 ) 224 225 // 226 // MAV_GOTO 227 /*Override command, pauses current mission execution and moves immediately to a position*/ 228 // 229 const ( 230 MAV_GOTO_DO_HOLD = 0 // Hold at the current position. | 231 MAV_GOTO_DO_CONTINUE = 1 // Continue with the next item in mission execution. | 232 MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2 // Hold at the current position of the system | 233 MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3 // Hold at the position specified in the parameters of the DO_HOLD action | 234 MAV_GOTO_ENUM_END = 4 // | 235 ) 236 237 // 238 // MAV_MODE 239 /*These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it 240 simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override.*/ 241 // 242 const ( 243 MAV_MODE_PREFLIGHT = 0 // System is not ready to fly, booting, calibrating, etc. No flag is set. | 244 MAV_MODE_MANUAL_DISARMED = 64 // System is allowed to be active, under manual (RC) control, no stabilization | 245 MAV_MODE_TEST_DISARMED = 66 // UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | 246 MAV_MODE_STABILIZE_DISARMED = 80 // System is allowed to be active, under assisted RC control. | 247 MAV_MODE_GUIDED_DISARMED = 88 // System is allowed to be active, under autonomous control, manual setpoint | 248 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) | 249 MAV_MODE_MANUAL_ARMED = 192 // System is allowed to be active, under manual (RC) control, no stabilization | 250 MAV_MODE_TEST_ARMED = 194 // UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | 251 MAV_MODE_STABILIZE_ARMED = 208 // System is allowed to be active, under assisted RC control. | 252 MAV_MODE_GUIDED_ARMED = 216 // System is allowed to be active, under autonomous control, manual setpoint | 253 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) | 254 MAV_MODE_ENUM_END = 221 // | 255 ) 256 257 // 258 // MAV_STATE 259 /**/ 260 // 261 const ( 262 MAV_STATE_UNINIT = 0 // Uninitialized system, state is unknown. | 263 MAV_STATE_BOOT = 1 // System is booting up. | 264 MAV_STATE_CALIBRATING = 2 // System is calibrating and not flight-ready. | 265 MAV_STATE_STANDBY = 3 // System is grounded and on standby. It can be launched any time. | 266 MAV_STATE_ACTIVE = 4 // System is active and might be already airborne. Motors are engaged. | 267 MAV_STATE_CRITICAL = 5 // System is in a non-normal flight mode. It can however still navigate. | 268 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. | 269 MAV_STATE_POWEROFF = 7 // System just initialized its power-down sequence, will shut down now. | 270 MAV_STATE_ENUM_END = 8 // | 271 ) 272 273 // 274 // MAV_COMPONENT 275 /**/ 276 // 277 const ( 278 MAV_COMP_ID_ALL = 0 // | 279 MAV_COMP_ID_CAMERA = 100 // | 280 MAV_COMP_ID_SERVO1 = 140 // | 281 MAV_COMP_ID_SERVO2 = 141 // | 282 MAV_COMP_ID_SERVO3 = 142 // | 283 MAV_COMP_ID_SERVO4 = 143 // | 284 MAV_COMP_ID_SERVO5 = 144 // | 285 MAV_COMP_ID_SERVO6 = 145 // | 286 MAV_COMP_ID_SERVO7 = 146 // | 287 MAV_COMP_ID_SERVO8 = 147 // | 288 MAV_COMP_ID_SERVO9 = 148 // | 289 MAV_COMP_ID_SERVO10 = 149 // | 290 MAV_COMP_ID_SERVO11 = 150 // | 291 MAV_COMP_ID_SERVO12 = 151 // | 292 MAV_COMP_ID_SERVO13 = 152 // | 293 MAV_COMP_ID_SERVO14 = 153 // | 294 MAV_COMP_ID_MAPPER = 180 // | 295 MAV_COMP_ID_MISSIONPLANNER = 190 // | 296 MAV_COMP_ID_PATHPLANNER = 195 // | 297 MAV_COMP_ID_IMU = 200 // | 298 MAV_COMP_ID_IMU_2 = 201 // | 299 MAV_COMP_ID_IMU_3 = 202 // | 300 MAV_COMP_ID_GPS = 220 // | 301 MAV_COMP_ID_UDP_BRIDGE = 240 // | 302 MAV_COMP_ID_UART_BRIDGE = 241 // | 303 MAV_COMP_ID_SYSTEM_CONTROL = 250 // | 304 MAV_COMPONENT_ENUM_END = 251 // | 305 ) 306 307 // 308 // MAV_SYS_STATUS_SENSOR 309 /*These encode the sensors whose status is sent as part of the SYS_STATUS message.*/ 310 // 311 const ( 312 MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 // 0x01 3D gyro | 313 MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 // 0x02 3D accelerometer | 314 MAV_SYS_STATUS_SENSOR_3D_MAG = 4 // 0x04 3D magnetometer | 315 MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 // 0x08 absolute pressure | 316 MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 // 0x10 differential pressure | 317 MAV_SYS_STATUS_SENSOR_GPS = 32 // 0x20 GPS | 318 MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 // 0x40 optical flow | 319 MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 // 0x80 computer vision position | 320 MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 // 0x100 laser based position | 321 MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 // 0x200 external ground truth (Vicon or Leica) | 322 MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 // 0x400 3D angular rate control | 323 MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 // 0x800 attitude stabilization | 324 MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 // 0x1000 yaw position | 325 MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 // 0x2000 z/altitude control | 326 MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 // 0x4000 x/y position control | 327 MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 // 0x8000 motor outputs / control | 328 MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 // 0x10000 rc receiver | 329 MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 // 0x20000 2nd 3D gyro | 330 MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 // 0x40000 2nd 3D accelerometer | 331 MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 // 0x80000 2nd 3D magnetometer | 332 MAV_SYS_STATUS_GEOFENCE = 1048576 // 0x100000 geofence | 333 MAV_SYS_STATUS_AHRS = 2097152 // 0x200000 AHRS subsystem health | 334 MAV_SYS_STATUS_TERRAIN = 4194304 // 0x400000 Terrain subsystem health | 335 MAV_SYS_STATUS_SENSOR_ENUM_END = 4194305 // | 336 ) 337 338 // 339 // MAV_FRAME 340 /**/ 341 // 342 const ( 343 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) | 344 MAV_FRAME_LOCAL_NED = 1 // Local coordinate frame, Z-up (x: north, y: east, z: down). | 345 MAV_FRAME_MISSION = 2 // NOT a coordinate frame, indicates a mission command. | 346 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. | 347 MAV_FRAME_LOCAL_ENU = 4 // Local coordinate frame, Z-down (x: east, y: north, z: up) | 348 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. | 349 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. | 350 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. | 351 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. | 352 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. | 353 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. | 354 MAV_FRAME_ENUM_END = 11 // | 355 ) 356 357 // 358 // MAVLINK_DATA_STREAM_TYPE 359 /**/ 360 // 361 const ( 362 MAVLINK_DATA_STREAM_IMG_JPEG = 1 // | 363 MAVLINK_DATA_STREAM_IMG_BMP = 2 // | 364 MAVLINK_DATA_STREAM_IMG_RAW8U = 3 // | 365 MAVLINK_DATA_STREAM_IMG_RAW32U = 4 // | 366 MAVLINK_DATA_STREAM_IMG_PGM = 5 // | 367 MAVLINK_DATA_STREAM_IMG_PNG = 6 // | 368 MAVLINK_DATA_STREAM_TYPE_ENUM_END = 7 // | 369 ) 370 371 // 372 // FENCE_ACTION 373 /**/ 374 // 375 const ( 376 FENCE_ACTION_NONE = 0 // Disable fenced mode | 377 FENCE_ACTION_GUIDED = 1 // Switched to guided mode to return point (fence point 0) | 378 FENCE_ACTION_REPORT = 2 // Report fence breach, but don't take action | 379 FENCE_ACTION_GUIDED_THR_PASS = 3 // Switched to guided mode to return point (fence point 0) with manual throttle control | 380 FENCE_ACTION_ENUM_END = 4 // | 381 ) 382 383 // 384 // FENCE_BREACH 385 /**/ 386 // 387 const ( 388 FENCE_BREACH_NONE = 0 // No last fence breach | 389 FENCE_BREACH_MINALT = 1 // Breached minimum altitude | 390 FENCE_BREACH_MAXALT = 2 // Breached maximum altitude | 391 FENCE_BREACH_BOUNDARY = 3 // Breached fence boundary | 392 FENCE_BREACH_ENUM_END = 4 // | 393 ) 394 395 // 396 // MAV_MOUNT_MODE 397 /*Enumeration of possible mount operation modes*/ 398 // 399 const ( 400 MAV_MOUNT_MODE_RETRACT = 0 // Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | 401 MAV_MOUNT_MODE_NEUTRAL = 1 // Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | 402 MAV_MOUNT_MODE_MAVLINK_TARGETING = 2 // Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | 403 MAV_MOUNT_MODE_RC_TARGETING = 3 // Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | 404 MAV_MOUNT_MODE_GPS_POINT = 4 // Load neutral position and start to point to Lat,Lon,Alt | 405 MAV_MOUNT_MODE_ENUM_END = 5 // | 406 ) 407 408 // 409 // MAV_CMD 410 /*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.*/ 411 // 412 const ( 413 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 | 414 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 | 415 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 | 416 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 | 417 MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 // Return to launch location | Empty | Empty | Empty | Empty | Empty | Empty | Empty | 418 MAV_CMD_NAV_LAND = 21 // Land at location | Empty | Empty | Empty | Desired yaw angle. | Latitude | Longitude | Altitude | 419 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 | 420 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 | 421 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 | 422 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 | 423 MAV_CMD_NAV_GUIDED_ENABLE = 92 // hand control over to an external controller | On / Off (> 0.5f on) | Empty | Empty | Empty | Empty | Empty | Empty | 424 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 | 425 MAV_CMD_CONDITION_DELAY = 112 // Delay mission state machine. | Delay in seconds (decimal) | Empty | Empty | Empty | Empty | Empty | Empty | 426 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 | 427 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 | 428 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 | 429 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 | 430 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 | 431 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 | 432 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 | 433 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 | 434 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 | 435 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 | 436 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 | 437 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 | 438 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 | 439 MAV_CMD_DO_FLIGHTTERMINATION = 185 // Terminate flight immediately | Flight termination activated if > 0.5 | Empty | Empty | Empty | Empty | Empty | Empty | 440 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 | 441 MAV_CMD_DO_GO_AROUND = 191 // Mission command to safely abort an autonmous landing. | Altitude (meters) | Empty | Empty | Empty | Empty | Empty | Empty | 442 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 | 443 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 | 444 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) | 445 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 | 446 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 | 447 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 | 448 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 | 449 MAV_CMD_DO_FENCE_ENABLE = 207 // Mission command to enable the geofence | enable? (0=disable, 1=enable) | Empty | Empty | Empty | Empty | Empty | Empty | 450 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 | 451 MAV_CMD_DO_INVERTED_FLIGHT = 210 // Change to/from inverted flight | inverted (0=normal, 1=inverted) | Empty | Empty | Empty | Empty | Empty | Empty | 452 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 | 453 MAV_CMD_DO_GUIDED_MASTER = 221 // set id of master controller | System ID | Component ID | Empty | Empty | Empty | Empty | Empty | 454 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 | 455 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 | 456 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 | 457 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 | 458 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 | 459 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 | 460 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 | 461 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) | 462 MAV_CMD_COMPONENT_ARM_DISARM = 400 // Arms / Disarms a component | 1 to arm, 0 to disarm | 463 MAV_CMD_START_RX_PAIR = 500 // Starts receiver pairing | 0:Spektrum | 0:Spektrum DSM2, 1:Spektrum DSMX | 464 MAV_CMD_ENUM_END = 501 // | 465 ) 466 467 // 468 // MAV_DATA_STREAM 469 /*Data stream IDs. A data stream is not a fixed set of messages, but rather a 470 recommendation to the autopilot software. Individual autopilots may or may not obey 471 the recommended messages.*/ 472 // 473 const ( 474 MAV_DATA_STREAM_ALL = 0 // Enable all data streams | 475 MAV_DATA_STREAM_RAW_SENSORS = 1 // Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | 476 MAV_DATA_STREAM_EXTENDED_STATUS = 2 // Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | 477 MAV_DATA_STREAM_RC_CHANNELS = 3 // Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | 478 MAV_DATA_STREAM_RAW_CONTROLLER = 4 // Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | 479 MAV_DATA_STREAM_POSITION = 6 // Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | 480 MAV_DATA_STREAM_EXTRA1 = 10 // Dependent on the autopilot | 481 MAV_DATA_STREAM_EXTRA2 = 11 // Dependent on the autopilot | 482 MAV_DATA_STREAM_EXTRA3 = 12 // Dependent on the autopilot | 483 MAV_DATA_STREAM_ENUM_END = 13 // | 484 ) 485 486 // 487 // MAV_ROI 488 /* The ROI (region of interest) for the vehicle. This can be 489 be used by the vehicle for camera/vehicle attitude alignment (see 490 MAV_CMD_NAV_ROI).*/ 491 // 492 const ( 493 MAV_ROI_NONE = 0 // No region of interest. | 494 MAV_ROI_WPNEXT = 1 // Point toward next MISSION. | 495 MAV_ROI_WPINDEX = 2 // Point toward given MISSION. | 496 MAV_ROI_LOCATION = 3 // Point toward fixed location. | 497 MAV_ROI_TARGET = 4 // Point toward of given id. | 498 MAV_ROI_ENUM_END = 5 // | 499 ) 500 501 // 502 // MAV_CMD_ACK 503 /*ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.*/ 504 // 505 const ( 506 MAV_CMD_ACK_OK = 1 // Command / mission item is ok. | 507 MAV_CMD_ACK_ERR_FAIL = 2 // Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | 508 MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 // The system is refusing to accept this command from this source / communication partner. | 509 MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 // Command or mission item is not supported, other commands would be accepted. | 510 MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 // The coordinate frame of this command / mission item is not supported. | 511 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. | 512 MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 // The X or latitude value is out of range. | 513 MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 // The Y or longitude value is out of range. | 514 MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 // The Z or altitude value is out of range. | 515 MAV_CMD_ACK_ENUM_END = 10 // | 516 ) 517 518 // 519 // MAV_PARAM_TYPE 520 /*Specifies the datatype of a MAVLink parameter.*/ 521 // 522 const ( 523 MAV_PARAM_TYPE_UINT8 = 1 // 8-bit unsigned integer | 524 MAV_PARAM_TYPE_INT8 = 2 // 8-bit signed integer | 525 MAV_PARAM_TYPE_UINT16 = 3 // 16-bit unsigned integer | 526 MAV_PARAM_TYPE_INT16 = 4 // 16-bit signed integer | 527 MAV_PARAM_TYPE_UINT32 = 5 // 32-bit unsigned integer | 528 MAV_PARAM_TYPE_INT32 = 6 // 32-bit signed integer | 529 MAV_PARAM_TYPE_UINT64 = 7 // 64-bit unsigned integer | 530 MAV_PARAM_TYPE_INT64 = 8 // 64-bit signed integer | 531 MAV_PARAM_TYPE_REAL32 = 9 // 32-bit floating-point | 532 MAV_PARAM_TYPE_REAL64 = 10 // 64-bit floating-point | 533 MAV_PARAM_TYPE_ENUM_END = 11 // | 534 ) 535 536 // 537 // MAV_RESULT 538 /*result from a mavlink command*/ 539 // 540 const ( 541 MAV_RESULT_ACCEPTED = 0 // Command ACCEPTED and EXECUTED | 542 MAV_RESULT_TEMPORARILY_REJECTED = 1 // Command TEMPORARY REJECTED/DENIED | 543 MAV_RESULT_DENIED = 2 // Command PERMANENTLY DENIED | 544 MAV_RESULT_UNSUPPORTED = 3 // Command UNKNOWN/UNSUPPORTED | 545 MAV_RESULT_FAILED = 4 // Command executed, but failed | 546 MAV_RESULT_ENUM_END = 5 // | 547 ) 548 549 // 550 // MAV_MISSION_RESULT 551 /*result in a mavlink mission ack*/ 552 // 553 const ( 554 MAV_MISSION_ACCEPTED = 0 // mission accepted OK | 555 MAV_MISSION_ERROR = 1 // generic error / not accepting mission commands at all right now | 556 MAV_MISSION_UNSUPPORTED_FRAME = 2 // coordinate frame is not supported | 557 MAV_MISSION_UNSUPPORTED = 3 // command is not supported | 558 MAV_MISSION_NO_SPACE = 4 // mission item exceeds storage space | 559 MAV_MISSION_INVALID = 5 // one of the parameters has an invalid value | 560 MAV_MISSION_INVALID_PARAM1 = 6 // param1 has an invalid value | 561 MAV_MISSION_INVALID_PARAM2 = 7 // param2 has an invalid value | 562 MAV_MISSION_INVALID_PARAM3 = 8 // param3 has an invalid value | 563 MAV_MISSION_INVALID_PARAM4 = 9 // param4 has an invalid value | 564 MAV_MISSION_INVALID_PARAM5_X = 10 // x/param5 has an invalid value | 565 MAV_MISSION_INVALID_PARAM6_Y = 11 // y/param6 has an invalid value | 566 MAV_MISSION_INVALID_PARAM7 = 12 // param7 has an invalid value | 567 MAV_MISSION_INVALID_SEQUENCE = 13 // received waypoint out of sequence | 568 MAV_MISSION_DENIED = 14 // not accepting any mission commands from this communication partner | 569 MAV_MISSION_RESULT_ENUM_END = 15 // | 570 ) 571 572 // 573 // MAV_SEVERITY 574 /*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/.*/ 575 // 576 const ( 577 MAV_SEVERITY_EMERGENCY = 0 // System is unusable. This is a "panic" condition. | 578 MAV_SEVERITY_ALERT = 1 // Action should be taken immediately. Indicates error in non-critical systems. | 579 MAV_SEVERITY_CRITICAL = 2 // Action must be taken immediately. Indicates failure in a primary system. | 580 MAV_SEVERITY_ERROR = 3 // Indicates an error in secondary/redundant systems. | 581 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. | 582 MAV_SEVERITY_NOTICE = 5 // An unusual event has occurred, though not an error condition. This should be investigated for the root cause. | 583 MAV_SEVERITY_INFO = 6 // Normal operational messages. Useful for logging. No action is required for these messages. | 584 MAV_SEVERITY_DEBUG = 7 // Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | 585 MAV_SEVERITY_ENUM_END = 8 // | 586 ) 587 588 // 589 // MAV_POWER_STATUS 590 /*Power supply status flags (bitmask)*/ 591 // 592 const ( 593 MAV_POWER_STATUS_BRICK_VALID = 1 // main brick power supply valid | 594 MAV_POWER_STATUS_SERVO_VALID = 2 // main servo power supply valid for FMU | 595 MAV_POWER_STATUS_USB_CONNECTED = 4 // USB power is connected | 596 MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 // peripheral supply is in over-current state | 597 MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 // hi-power peripheral supply is in over-current state | 598 MAV_POWER_STATUS_CHANGED = 32 // Power status has changed since boot | 599 MAV_POWER_STATUS_ENUM_END = 33 // | 600 ) 601 602 // 603 // SERIAL_CONTROL_DEV 604 /*SERIAL_CONTROL device types*/ 605 // 606 const ( 607 SERIAL_CONTROL_DEV_TELEM1 = 0 // First telemetry port | 608 SERIAL_CONTROL_DEV_TELEM2 = 1 // Second telemetry port | 609 SERIAL_CONTROL_DEV_GPS1 = 2 // First GPS port | 610 SERIAL_CONTROL_DEV_GPS2 = 3 // Second GPS port | 611 SERIAL_CONTROL_DEV_ENUM_END = 4 // | 612 ) 613 614 // 615 // SERIAL_CONTROL_FLAG 616 /*SERIAL_CONTROL flags (bitmask)*/ 617 // 618 const ( 619 SERIAL_CONTROL_FLAG_REPLY = 1 // Set if this is a reply | 620 SERIAL_CONTROL_FLAG_RESPOND = 2 // Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | 621 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 | 622 SERIAL_CONTROL_FLAG_BLOCKING = 8 // Block on writes to the serial port | 623 SERIAL_CONTROL_FLAG_MULTI = 16 // Send multiple replies until port is drained | 624 SERIAL_CONTROL_FLAG_ENUM_END = 17 // | 625 ) 626 627 // 628 // MAV_DISTANCE_SENSOR 629 /*Enumeration of distance sensor types*/ 630 // 631 const ( 632 MAV_DISTANCE_SENSOR_LASER = 0 // Laser altimeter, e.g. LightWare SF02/F or PulsedLight units | 633 MAV_DISTANCE_SENSOR_ULTRASOUND = 1 // Ultrasound altimeter, e.g. MaxBotix units | 634 MAV_DISTANCE_SENSOR_ENUM_END = 2 // | 635 ) 636 637 // 638 // MESSAGE HEARTBEAT 639 // 640 // MAVLINK_MSG_ID_HEARTBEAT 0 641 // 642 // MAVLINK_MSG_ID_HEARTBEAT_LEN 9 643 // 644 // MAVLINK_MSG_ID_HEARTBEAT_CRC 50 645 // 646 // 647 type Heartbeat struct { 648 CUSTOM_MODE uint32 // A bitfield for use for autopilot-specific flags. 649 TYPE uint8 // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) 650 AUTOPILOT uint8 // Autopilot type / class. defined in MAV_AUTOPILOT ENUM 651 BASE_MODE uint8 // System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h 652 SYSTEM_STATUS uint8 // System status flag, see MAV_STATE ENUM 653 MAVLINK_VERSION uint8 // MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version 654 } 655 656 // NewHeartbeat returns a new Heartbeat 657 func NewHeartbeat(CUSTOM_MODE uint32, TYPE uint8, AUTOPILOT uint8, BASE_MODE uint8, SYSTEM_STATUS uint8, MAVLINK_VERSION uint8) *Heartbeat { 658 m := Heartbeat{} 659 m.CUSTOM_MODE = CUSTOM_MODE 660 m.TYPE = TYPE 661 m.AUTOPILOT = AUTOPILOT 662 m.BASE_MODE = BASE_MODE 663 m.SYSTEM_STATUS = SYSTEM_STATUS 664 m.MAVLINK_VERSION = MAVLINK_VERSION 665 return &m 666 } 667 668 // Id returns the Heartbeat Message ID 669 func (*Heartbeat) Id() uint8 { 670 return 0 671 } 672 673 // Len returns the Heartbeat Message Length 674 func (*Heartbeat) Len() uint8 { 675 return 9 676 } 677 678 // Crc returns the Heartbeat Message CRC 679 func (*Heartbeat) Crc() uint8 { 680 return 50 681 } 682 683 // Pack returns a packed byte array which represents a Heartbeat payload 684 func (m *Heartbeat) Pack() []byte { 685 data := new(bytes.Buffer) 686 binary.Write(data, binary.LittleEndian, m.CUSTOM_MODE) 687 binary.Write(data, binary.LittleEndian, m.TYPE) 688 binary.Write(data, binary.LittleEndian, m.AUTOPILOT) 689 binary.Write(data, binary.LittleEndian, m.BASE_MODE) 690 binary.Write(data, binary.LittleEndian, m.SYSTEM_STATUS) 691 binary.Write(data, binary.LittleEndian, m.MAVLINK_VERSION) 692 return data.Bytes() 693 } 694 695 // Decode accepts a packed byte array and populates the fields of the Heartbeat 696 func (m *Heartbeat) Decode(buf []byte) { 697 data := bytes.NewBuffer(buf) 698 binary.Read(data, binary.LittleEndian, &m.CUSTOM_MODE) 699 binary.Read(data, binary.LittleEndian, &m.TYPE) 700 binary.Read(data, binary.LittleEndian, &m.AUTOPILOT) 701 binary.Read(data, binary.LittleEndian, &m.BASE_MODE) 702 binary.Read(data, binary.LittleEndian, &m.SYSTEM_STATUS) 703 binary.Read(data, binary.LittleEndian, &m.MAVLINK_VERSION) 704 } 705 706 // 707 // MESSAGE SYS_STATUS 708 // 709 // MAVLINK_MSG_ID_SYS_STATUS 1 710 // 711 // MAVLINK_MSG_ID_SYS_STATUS_LEN 31 712 // 713 // MAVLINK_MSG_ID_SYS_STATUS_CRC 124 714 // 715 // 716 type SysStatus struct { 717 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 718 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 719 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 720 LOAD uint16 // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 721 VOLTAGE_BATTERY uint16 // Battery voltage, in millivolts (1 = 1 millivolt) 722 CURRENT_BATTERY int16 // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current 723 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) 724 ERRORS_COMM uint16 // Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) 725 ERRORS_COUNT1 uint16 // Autopilot-specific errors 726 ERRORS_COUNT2 uint16 // Autopilot-specific errors 727 ERRORS_COUNT3 uint16 // Autopilot-specific errors 728 ERRORS_COUNT4 uint16 // Autopilot-specific errors 729 BATTERY_REMAINING int8 // Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery 730 } 731 732 // NewSysStatus returns a new SysStatus 733 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 { 734 m := SysStatus{} 735 m.ONBOARD_CONTROL_SENSORS_PRESENT = ONBOARD_CONTROL_SENSORS_PRESENT 736 m.ONBOARD_CONTROL_SENSORS_ENABLED = ONBOARD_CONTROL_SENSORS_ENABLED 737 m.ONBOARD_CONTROL_SENSORS_HEALTH = ONBOARD_CONTROL_SENSORS_HEALTH 738 m.LOAD = LOAD 739 m.VOLTAGE_BATTERY = VOLTAGE_BATTERY 740 m.CURRENT_BATTERY = CURRENT_BATTERY 741 m.DROP_RATE_COMM = DROP_RATE_COMM 742 m.ERRORS_COMM = ERRORS_COMM 743 m.ERRORS_COUNT1 = ERRORS_COUNT1 744 m.ERRORS_COUNT2 = ERRORS_COUNT2 745 m.ERRORS_COUNT3 = ERRORS_COUNT3 746 m.ERRORS_COUNT4 = ERRORS_COUNT4 747 m.BATTERY_REMAINING = BATTERY_REMAINING 748 return &m 749 } 750 751 // Id returns the SysStatus Message ID 752 func (*SysStatus) Id() uint8 { 753 return 1 754 } 755 756 // Len returns the SysStatus Message Length 757 func (*SysStatus) Len() uint8 { 758 return 31 759 } 760 761 // Crc returns the SysStatus Message CRC 762 func (*SysStatus) Crc() uint8 { 763 return 124 764 } 765 766 // Pack returns a packed byte array which represents a SysStatus payload 767 func (m *SysStatus) Pack() []byte { 768 data := new(bytes.Buffer) 769 binary.Write(data, binary.LittleEndian, m.ONBOARD_CONTROL_SENSORS_PRESENT) 770 binary.Write(data, binary.LittleEndian, m.ONBOARD_CONTROL_SENSORS_ENABLED) 771 binary.Write(data, binary.LittleEndian, m.ONBOARD_CONTROL_SENSORS_HEALTH) 772 binary.Write(data, binary.LittleEndian, m.LOAD) 773 binary.Write(data, binary.LittleEndian, m.VOLTAGE_BATTERY) 774 binary.Write(data, binary.LittleEndian, m.CURRENT_BATTERY) 775 binary.Write(data, binary.LittleEndian, m.DROP_RATE_COMM) 776 binary.Write(data, binary.LittleEndian, m.ERRORS_COMM) 777 binary.Write(data, binary.LittleEndian, m.ERRORS_COUNT1) 778 binary.Write(data, binary.LittleEndian, m.ERRORS_COUNT2) 779 binary.Write(data, binary.LittleEndian, m.ERRORS_COUNT3) 780 binary.Write(data, binary.LittleEndian, m.ERRORS_COUNT4) 781 binary.Write(data, binary.LittleEndian, m.BATTERY_REMAINING) 782 return data.Bytes() 783 } 784 785 // Decode accepts a packed byte array and populates the fields of the SysStatus 786 func (m *SysStatus) Decode(buf []byte) { 787 data := bytes.NewBuffer(buf) 788 binary.Read(data, binary.LittleEndian, &m.ONBOARD_CONTROL_SENSORS_PRESENT) 789 binary.Read(data, binary.LittleEndian, &m.ONBOARD_CONTROL_SENSORS_ENABLED) 790 binary.Read(data, binary.LittleEndian, &m.ONBOARD_CONTROL_SENSORS_HEALTH) 791 binary.Read(data, binary.LittleEndian, &m.LOAD) 792 binary.Read(data, binary.LittleEndian, &m.VOLTAGE_BATTERY) 793 binary.Read(data, binary.LittleEndian, &m.CURRENT_BATTERY) 794 binary.Read(data, binary.LittleEndian, &m.DROP_RATE_COMM) 795 binary.Read(data, binary.LittleEndian, &m.ERRORS_COMM) 796 binary.Read(data, binary.LittleEndian, &m.ERRORS_COUNT1) 797 binary.Read(data, binary.LittleEndian, &m.ERRORS_COUNT2) 798 binary.Read(data, binary.LittleEndian, &m.ERRORS_COUNT3) 799 binary.Read(data, binary.LittleEndian, &m.ERRORS_COUNT4) 800 binary.Read(data, binary.LittleEndian, &m.BATTERY_REMAINING) 801 } 802 803 // 804 // MESSAGE SYSTEM_TIME 805 // 806 // MAVLINK_MSG_ID_SYSTEM_TIME 2 807 // 808 // MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 809 // 810 // MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137 811 // 812 // 813 type SystemTime struct { 814 TIME_UNIX_USEC uint64 // Timestamp of the master clock in microseconds since UNIX epoch. 815 TIME_BOOT_MS uint32 // Timestamp of the component clock since boot time in milliseconds. 816 } 817 818 // NewSystemTime returns a new SystemTime 819 func NewSystemTime(TIME_UNIX_USEC uint64, TIME_BOOT_MS uint32) *SystemTime { 820 m := SystemTime{} 821 m.TIME_UNIX_USEC = TIME_UNIX_USEC 822 m.TIME_BOOT_MS = TIME_BOOT_MS 823 return &m 824 } 825 826 // Id returns the SystemTime Message ID 827 func (*SystemTime) Id() uint8 { 828 return 2 829 } 830 831 // Len returns the SystemTime Message Length 832 func (*SystemTime) Len() uint8 { 833 return 12 834 } 835 836 // Crc returns the SystemTime Message CRC 837 func (*SystemTime) Crc() uint8 { 838 return 137 839 } 840 841 // Pack returns a packed byte array which represents a SystemTime payload 842 func (m *SystemTime) Pack() []byte { 843 data := new(bytes.Buffer) 844 binary.Write(data, binary.LittleEndian, m.TIME_UNIX_USEC) 845 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 846 return data.Bytes() 847 } 848 849 // Decode accepts a packed byte array and populates the fields of the SystemTime 850 func (m *SystemTime) Decode(buf []byte) { 851 data := bytes.NewBuffer(buf) 852 binary.Read(data, binary.LittleEndian, &m.TIME_UNIX_USEC) 853 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 854 } 855 856 // 857 // MESSAGE PING 858 // 859 // MAVLINK_MSG_ID_PING 4 860 // 861 // MAVLINK_MSG_ID_PING_LEN 14 862 // 863 // MAVLINK_MSG_ID_PING_CRC 237 864 // 865 // 866 type Ping struct { 867 TIME_USEC uint64 // Unix timestamp in microseconds 868 SEQ uint32 // PING sequence 869 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 870 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 871 } 872 873 // NewPing returns a new Ping 874 func NewPing(TIME_USEC uint64, SEQ uint32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *Ping { 875 m := Ping{} 876 m.TIME_USEC = TIME_USEC 877 m.SEQ = SEQ 878 m.TARGET_SYSTEM = TARGET_SYSTEM 879 m.TARGET_COMPONENT = TARGET_COMPONENT 880 return &m 881 } 882 883 // Id returns the Ping Message ID 884 func (*Ping) Id() uint8 { 885 return 4 886 } 887 888 // Len returns the Ping Message Length 889 func (*Ping) Len() uint8 { 890 return 14 891 } 892 893 // Crc returns the Ping Message CRC 894 func (*Ping) Crc() uint8 { 895 return 237 896 } 897 898 // Pack returns a packed byte array which represents a Ping payload 899 func (m *Ping) Pack() []byte { 900 data := new(bytes.Buffer) 901 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 902 binary.Write(data, binary.LittleEndian, m.SEQ) 903 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 904 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 905 return data.Bytes() 906 } 907 908 // Decode accepts a packed byte array and populates the fields of the Ping 909 func (m *Ping) Decode(buf []byte) { 910 data := bytes.NewBuffer(buf) 911 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 912 binary.Read(data, binary.LittleEndian, &m.SEQ) 913 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 914 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 915 } 916 917 // 918 // MESSAGE CHANGE_OPERATOR_CONTROL 919 // 920 // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 921 // 922 // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 923 // 924 // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC 217 925 // 926 // 927 type ChangeOperatorControl struct { 928 TARGET_SYSTEM uint8 // System the GCS requests control for 929 CONTROL_REQUEST uint8 // 0: request control of this MAV, 1: Release control of this MAV 930 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. 931 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 "!?,.-" 932 } 933 934 // NewChangeOperatorControl returns a new ChangeOperatorControl 935 func NewChangeOperatorControl(TARGET_SYSTEM uint8, CONTROL_REQUEST uint8, VERSION uint8, PASSKEY [25]uint8) *ChangeOperatorControl { 936 m := ChangeOperatorControl{} 937 m.TARGET_SYSTEM = TARGET_SYSTEM 938 m.CONTROL_REQUEST = CONTROL_REQUEST 939 m.VERSION = VERSION 940 m.PASSKEY = PASSKEY 941 return &m 942 } 943 944 // Id returns the ChangeOperatorControl Message ID 945 func (*ChangeOperatorControl) Id() uint8 { 946 return 5 947 } 948 949 // Len returns the ChangeOperatorControl Message Length 950 func (*ChangeOperatorControl) Len() uint8 { 951 return 28 952 } 953 954 // Crc returns the ChangeOperatorControl Message CRC 955 func (*ChangeOperatorControl) Crc() uint8 { 956 return 217 957 } 958 959 // Pack returns a packed byte array which represents a ChangeOperatorControl payload 960 func (m *ChangeOperatorControl) Pack() []byte { 961 data := new(bytes.Buffer) 962 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 963 binary.Write(data, binary.LittleEndian, m.CONTROL_REQUEST) 964 binary.Write(data, binary.LittleEndian, m.VERSION) 965 binary.Write(data, binary.LittleEndian, m.PASSKEY) 966 return data.Bytes() 967 } 968 969 // Decode accepts a packed byte array and populates the fields of the ChangeOperatorControl 970 func (m *ChangeOperatorControl) Decode(buf []byte) { 971 data := bytes.NewBuffer(buf) 972 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 973 binary.Read(data, binary.LittleEndian, &m.CONTROL_REQUEST) 974 binary.Read(data, binary.LittleEndian, &m.VERSION) 975 binary.Read(data, binary.LittleEndian, &m.PASSKEY) 976 } 977 978 const ( 979 MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_passkey_LEN = 25 980 ) 981 982 // 983 // MESSAGE CHANGE_OPERATOR_CONTROL_ACK 984 // 985 // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 986 // 987 // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 988 // 989 // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104 990 // 991 // 992 type ChangeOperatorControlAck struct { 993 GCS_SYSTEM_ID uint8 // ID of the GCS this message 994 CONTROL_REQUEST uint8 // 0: request control of this MAV, 1: Release control of this MAV 995 ACK uint8 // 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control 996 } 997 998 // NewChangeOperatorControlAck returns a new ChangeOperatorControlAck 999 func NewChangeOperatorControlAck(GCS_SYSTEM_ID uint8, CONTROL_REQUEST uint8, ACK uint8) *ChangeOperatorControlAck { 1000 m := ChangeOperatorControlAck{} 1001 m.GCS_SYSTEM_ID = GCS_SYSTEM_ID 1002 m.CONTROL_REQUEST = CONTROL_REQUEST 1003 m.ACK = ACK 1004 return &m 1005 } 1006 1007 // Id returns the ChangeOperatorControlAck Message ID 1008 func (*ChangeOperatorControlAck) Id() uint8 { 1009 return 6 1010 } 1011 1012 // Len returns the ChangeOperatorControlAck Message Length 1013 func (*ChangeOperatorControlAck) Len() uint8 { 1014 return 3 1015 } 1016 1017 // Crc returns the ChangeOperatorControlAck Message CRC 1018 func (*ChangeOperatorControlAck) Crc() uint8 { 1019 return 104 1020 } 1021 1022 // Pack returns a packed byte array which represents a ChangeOperatorControlAck payload 1023 func (m *ChangeOperatorControlAck) Pack() []byte { 1024 data := new(bytes.Buffer) 1025 binary.Write(data, binary.LittleEndian, m.GCS_SYSTEM_ID) 1026 binary.Write(data, binary.LittleEndian, m.CONTROL_REQUEST) 1027 binary.Write(data, binary.LittleEndian, m.ACK) 1028 return data.Bytes() 1029 } 1030 1031 // Decode accepts a packed byte array and populates the fields of the ChangeOperatorControlAck 1032 func (m *ChangeOperatorControlAck) Decode(buf []byte) { 1033 data := bytes.NewBuffer(buf) 1034 binary.Read(data, binary.LittleEndian, &m.GCS_SYSTEM_ID) 1035 binary.Read(data, binary.LittleEndian, &m.CONTROL_REQUEST) 1036 binary.Read(data, binary.LittleEndian, &m.ACK) 1037 } 1038 1039 // 1040 // MESSAGE AUTH_KEY 1041 // 1042 // MAVLINK_MSG_ID_AUTH_KEY 7 1043 // 1044 // MAVLINK_MSG_ID_AUTH_KEY_LEN 32 1045 // 1046 // MAVLINK_MSG_ID_AUTH_KEY_CRC 119 1047 // 1048 // 1049 type AuthKey struct { 1050 KEY [32]uint8 // key 1051 } 1052 1053 // NewAuthKey returns a new AuthKey 1054 func NewAuthKey(KEY [32]uint8) *AuthKey { 1055 m := AuthKey{} 1056 m.KEY = KEY 1057 return &m 1058 } 1059 1060 // Id returns the AuthKey Message ID 1061 func (*AuthKey) Id() uint8 { 1062 return 7 1063 } 1064 1065 // Len returns the AuthKey Message Length 1066 func (*AuthKey) Len() uint8 { 1067 return 32 1068 } 1069 1070 // Crc returns the AuthKey Message CRC 1071 func (*AuthKey) Crc() uint8 { 1072 return 119 1073 } 1074 1075 // Pack returns a packed byte array which represents a AuthKey payload 1076 func (m *AuthKey) Pack() []byte { 1077 data := new(bytes.Buffer) 1078 binary.Write(data, binary.LittleEndian, m.KEY) 1079 return data.Bytes() 1080 } 1081 1082 // Decode accepts a packed byte array and populates the fields of the AuthKey 1083 func (m *AuthKey) Decode(buf []byte) { 1084 data := bytes.NewBuffer(buf) 1085 binary.Read(data, binary.LittleEndian, &m.KEY) 1086 } 1087 1088 const ( 1089 MAVLINK_MSG_AUTH_KEY_FIELD_key_LEN = 32 1090 ) 1091 1092 // 1093 // MESSAGE SET_MODE 1094 // 1095 // MAVLINK_MSG_ID_SET_MODE 11 1096 // 1097 // MAVLINK_MSG_ID_SET_MODE_LEN 6 1098 // 1099 // MAVLINK_MSG_ID_SET_MODE_CRC 89 1100 // 1101 // 1102 type SetMode struct { 1103 CUSTOM_MODE uint32 // The new autopilot-specific mode. This field can be ignored by an autopilot. 1104 TARGET_SYSTEM uint8 // The system setting the mode 1105 BASE_MODE uint8 // The new base mode 1106 } 1107 1108 // NewSetMode returns a new SetMode 1109 func NewSetMode(CUSTOM_MODE uint32, TARGET_SYSTEM uint8, BASE_MODE uint8) *SetMode { 1110 m := SetMode{} 1111 m.CUSTOM_MODE = CUSTOM_MODE 1112 m.TARGET_SYSTEM = TARGET_SYSTEM 1113 m.BASE_MODE = BASE_MODE 1114 return &m 1115 } 1116 1117 // Id returns the SetMode Message ID 1118 func (*SetMode) Id() uint8 { 1119 return 11 1120 } 1121 1122 // Len returns the SetMode Message Length 1123 func (*SetMode) Len() uint8 { 1124 return 6 1125 } 1126 1127 // Crc returns the SetMode Message CRC 1128 func (*SetMode) Crc() uint8 { 1129 return 89 1130 } 1131 1132 // Pack returns a packed byte array which represents a SetMode payload 1133 func (m *SetMode) Pack() []byte { 1134 data := new(bytes.Buffer) 1135 binary.Write(data, binary.LittleEndian, m.CUSTOM_MODE) 1136 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 1137 binary.Write(data, binary.LittleEndian, m.BASE_MODE) 1138 return data.Bytes() 1139 } 1140 1141 // Decode accepts a packed byte array and populates the fields of the SetMode 1142 func (m *SetMode) Decode(buf []byte) { 1143 data := bytes.NewBuffer(buf) 1144 binary.Read(data, binary.LittleEndian, &m.CUSTOM_MODE) 1145 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 1146 binary.Read(data, binary.LittleEndian, &m.BASE_MODE) 1147 } 1148 1149 // 1150 // MESSAGE PARAM_REQUEST_READ 1151 // 1152 // MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 1153 // 1154 // MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 1155 // 1156 // MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214 1157 // 1158 // 1159 type ParamRequestRead struct { 1160 PARAM_INDEX int16 // Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) 1161 TARGET_SYSTEM uint8 // System ID 1162 TARGET_COMPONENT uint8 // Component ID 1163 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 1164 } 1165 1166 // NewParamRequestRead returns a new ParamRequestRead 1167 func NewParamRequestRead(PARAM_INDEX int16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, PARAM_ID [16]uint8) *ParamRequestRead { 1168 m := ParamRequestRead{} 1169 m.PARAM_INDEX = PARAM_INDEX 1170 m.TARGET_SYSTEM = TARGET_SYSTEM 1171 m.TARGET_COMPONENT = TARGET_COMPONENT 1172 m.PARAM_ID = PARAM_ID 1173 return &m 1174 } 1175 1176 // Id returns the ParamRequestRead Message ID 1177 func (*ParamRequestRead) Id() uint8 { 1178 return 20 1179 } 1180 1181 // Len returns the ParamRequestRead Message Length 1182 func (*ParamRequestRead) Len() uint8 { 1183 return 20 1184 } 1185 1186 // Crc returns the ParamRequestRead Message CRC 1187 func (*ParamRequestRead) Crc() uint8 { 1188 return 214 1189 } 1190 1191 // Pack returns a packed byte array which represents a ParamRequestRead payload 1192 func (m *ParamRequestRead) Pack() []byte { 1193 data := new(bytes.Buffer) 1194 binary.Write(data, binary.LittleEndian, m.PARAM_INDEX) 1195 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 1196 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 1197 binary.Write(data, binary.LittleEndian, m.PARAM_ID) 1198 return data.Bytes() 1199 } 1200 1201 // Decode accepts a packed byte array and populates the fields of the ParamRequestRead 1202 func (m *ParamRequestRead) Decode(buf []byte) { 1203 data := bytes.NewBuffer(buf) 1204 binary.Read(data, binary.LittleEndian, &m.PARAM_INDEX) 1205 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 1206 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 1207 binary.Read(data, binary.LittleEndian, &m.PARAM_ID) 1208 } 1209 1210 const ( 1211 MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_param_id_LEN = 16 1212 ) 1213 1214 // 1215 // MESSAGE PARAM_REQUEST_LIST 1216 // 1217 // MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 1218 // 1219 // MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 1220 // 1221 // MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC 159 1222 // 1223 // 1224 type ParamRequestList struct { 1225 TARGET_SYSTEM uint8 // System ID 1226 TARGET_COMPONENT uint8 // Component ID 1227 } 1228 1229 // NewParamRequestList returns a new ParamRequestList 1230 func NewParamRequestList(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *ParamRequestList { 1231 m := ParamRequestList{} 1232 m.TARGET_SYSTEM = TARGET_SYSTEM 1233 m.TARGET_COMPONENT = TARGET_COMPONENT 1234 return &m 1235 } 1236 1237 // Id returns the ParamRequestList Message ID 1238 func (*ParamRequestList) Id() uint8 { 1239 return 21 1240 } 1241 1242 // Len returns the ParamRequestList Message Length 1243 func (*ParamRequestList) Len() uint8 { 1244 return 2 1245 } 1246 1247 // Crc returns the ParamRequestList Message CRC 1248 func (*ParamRequestList) Crc() uint8 { 1249 return 159 1250 } 1251 1252 // Pack returns a packed byte array which represents a ParamRequestList payload 1253 func (m *ParamRequestList) Pack() []byte { 1254 data := new(bytes.Buffer) 1255 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 1256 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 1257 return data.Bytes() 1258 } 1259 1260 // Decode accepts a packed byte array and populates the fields of the ParamRequestList 1261 func (m *ParamRequestList) Decode(buf []byte) { 1262 data := bytes.NewBuffer(buf) 1263 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 1264 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 1265 } 1266 1267 // 1268 // MESSAGE PARAM_VALUE 1269 // 1270 // MAVLINK_MSG_ID_PARAM_VALUE 22 1271 // 1272 // MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 1273 // 1274 // MAVLINK_MSG_ID_PARAM_VALUE_CRC 220 1275 // 1276 // 1277 type ParamValue struct { 1278 PARAM_VALUE float32 // Onboard parameter value 1279 PARAM_COUNT uint16 // Total number of onboard parameters 1280 PARAM_INDEX uint16 // Index of this onboard parameter 1281 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 1282 PARAM_TYPE uint8 // Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. 1283 } 1284 1285 // NewParamValue returns a new ParamValue 1286 func NewParamValue(PARAM_VALUE float32, PARAM_COUNT uint16, PARAM_INDEX uint16, PARAM_ID [16]uint8, PARAM_TYPE uint8) *ParamValue { 1287 m := ParamValue{} 1288 m.PARAM_VALUE = PARAM_VALUE 1289 m.PARAM_COUNT = PARAM_COUNT 1290 m.PARAM_INDEX = PARAM_INDEX 1291 m.PARAM_ID = PARAM_ID 1292 m.PARAM_TYPE = PARAM_TYPE 1293 return &m 1294 } 1295 1296 // Id returns the ParamValue Message ID 1297 func (*ParamValue) Id() uint8 { 1298 return 22 1299 } 1300 1301 // Len returns the ParamValue Message Length 1302 func (*ParamValue) Len() uint8 { 1303 return 25 1304 } 1305 1306 // Crc returns the ParamValue Message CRC 1307 func (*ParamValue) Crc() uint8 { 1308 return 220 1309 } 1310 1311 // Pack returns a packed byte array which represents a ParamValue payload 1312 func (m *ParamValue) Pack() []byte { 1313 data := new(bytes.Buffer) 1314 binary.Write(data, binary.LittleEndian, m.PARAM_VALUE) 1315 binary.Write(data, binary.LittleEndian, m.PARAM_COUNT) 1316 binary.Write(data, binary.LittleEndian, m.PARAM_INDEX) 1317 binary.Write(data, binary.LittleEndian, m.PARAM_ID) 1318 binary.Write(data, binary.LittleEndian, m.PARAM_TYPE) 1319 return data.Bytes() 1320 } 1321 1322 // Decode accepts a packed byte array and populates the fields of the ParamValue 1323 func (m *ParamValue) Decode(buf []byte) { 1324 data := bytes.NewBuffer(buf) 1325 binary.Read(data, binary.LittleEndian, &m.PARAM_VALUE) 1326 binary.Read(data, binary.LittleEndian, &m.PARAM_COUNT) 1327 binary.Read(data, binary.LittleEndian, &m.PARAM_INDEX) 1328 binary.Read(data, binary.LittleEndian, &m.PARAM_ID) 1329 binary.Read(data, binary.LittleEndian, &m.PARAM_TYPE) 1330 } 1331 1332 const ( 1333 MAVLINK_MSG_PARAM_VALUE_FIELD_param_id_LEN = 16 1334 ) 1335 1336 // 1337 // MESSAGE PARAM_SET 1338 // 1339 // MAVLINK_MSG_ID_PARAM_SET 23 1340 // 1341 // MAVLINK_MSG_ID_PARAM_SET_LEN 23 1342 // 1343 // MAVLINK_MSG_ID_PARAM_SET_CRC 168 1344 // 1345 // 1346 type ParamSet struct { 1347 PARAM_VALUE float32 // Onboard parameter value 1348 TARGET_SYSTEM uint8 // System ID 1349 TARGET_COMPONENT uint8 // Component ID 1350 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 1351 PARAM_TYPE uint8 // Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. 1352 } 1353 1354 // NewParamSet returns a new ParamSet 1355 func NewParamSet(PARAM_VALUE float32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, PARAM_ID [16]uint8, PARAM_TYPE uint8) *ParamSet { 1356 m := ParamSet{} 1357 m.PARAM_VALUE = PARAM_VALUE 1358 m.TARGET_SYSTEM = TARGET_SYSTEM 1359 m.TARGET_COMPONENT = TARGET_COMPONENT 1360 m.PARAM_ID = PARAM_ID 1361 m.PARAM_TYPE = PARAM_TYPE 1362 return &m 1363 } 1364 1365 // Id returns the ParamSet Message ID 1366 func (*ParamSet) Id() uint8 { 1367 return 23 1368 } 1369 1370 // Len returns the ParamSet Message Length 1371 func (*ParamSet) Len() uint8 { 1372 return 23 1373 } 1374 1375 // Crc returns the ParamSet Message CRC 1376 func (*ParamSet) Crc() uint8 { 1377 return 168 1378 } 1379 1380 // Pack returns a packed byte array which represents a ParamSet payload 1381 func (m *ParamSet) Pack() []byte { 1382 data := new(bytes.Buffer) 1383 binary.Write(data, binary.LittleEndian, m.PARAM_VALUE) 1384 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 1385 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 1386 binary.Write(data, binary.LittleEndian, m.PARAM_ID) 1387 binary.Write(data, binary.LittleEndian, m.PARAM_TYPE) 1388 return data.Bytes() 1389 } 1390 1391 // Decode accepts a packed byte array and populates the fields of the ParamSet 1392 func (m *ParamSet) Decode(buf []byte) { 1393 data := bytes.NewBuffer(buf) 1394 binary.Read(data, binary.LittleEndian, &m.PARAM_VALUE) 1395 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 1396 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 1397 binary.Read(data, binary.LittleEndian, &m.PARAM_ID) 1398 binary.Read(data, binary.LittleEndian, &m.PARAM_TYPE) 1399 } 1400 1401 const ( 1402 MAVLINK_MSG_PARAM_SET_FIELD_param_id_LEN = 16 1403 ) 1404 1405 // 1406 // MESSAGE GPS_RAW_INT 1407 // 1408 // MAVLINK_MSG_ID_GPS_RAW_INT 24 1409 // 1410 // MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 1411 // 1412 // MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24 1413 // 1414 // 1415 type GpsRawInt struct { 1416 TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) 1417 LAT int32 // Latitude (WGS84), in degrees * 1E7 1418 LON int32 // Longitude (WGS84), in degrees * 1E7 1419 ALT int32 // Altitude (WGS84), in meters * 1000 (positive for up) 1420 EPH uint16 // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX 1421 EPV uint16 // GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX 1422 VEL uint16 // GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX 1423 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 1424 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. 1425 SATELLITES_VISIBLE uint8 // Number of satellites visible. If unknown, set to 255 1426 } 1427 1428 // NewGpsRawInt returns a new GpsRawInt 1429 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 { 1430 m := GpsRawInt{} 1431 m.TIME_USEC = TIME_USEC 1432 m.LAT = LAT 1433 m.LON = LON 1434 m.ALT = ALT 1435 m.EPH = EPH 1436 m.EPV = EPV 1437 m.VEL = VEL 1438 m.COG = COG 1439 m.FIX_TYPE = FIX_TYPE 1440 m.SATELLITES_VISIBLE = SATELLITES_VISIBLE 1441 return &m 1442 } 1443 1444 // Id returns the GpsRawInt Message ID 1445 func (*GpsRawInt) Id() uint8 { 1446 return 24 1447 } 1448 1449 // Len returns the GpsRawInt Message Length 1450 func (*GpsRawInt) Len() uint8 { 1451 return 30 1452 } 1453 1454 // Crc returns the GpsRawInt Message CRC 1455 func (*GpsRawInt) Crc() uint8 { 1456 return 24 1457 } 1458 1459 // Pack returns a packed byte array which represents a GpsRawInt payload 1460 func (m *GpsRawInt) Pack() []byte { 1461 data := new(bytes.Buffer) 1462 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 1463 binary.Write(data, binary.LittleEndian, m.LAT) 1464 binary.Write(data, binary.LittleEndian, m.LON) 1465 binary.Write(data, binary.LittleEndian, m.ALT) 1466 binary.Write(data, binary.LittleEndian, m.EPH) 1467 binary.Write(data, binary.LittleEndian, m.EPV) 1468 binary.Write(data, binary.LittleEndian, m.VEL) 1469 binary.Write(data, binary.LittleEndian, m.COG) 1470 binary.Write(data, binary.LittleEndian, m.FIX_TYPE) 1471 binary.Write(data, binary.LittleEndian, m.SATELLITES_VISIBLE) 1472 return data.Bytes() 1473 } 1474 1475 // Decode accepts a packed byte array and populates the fields of the GpsRawInt 1476 func (m *GpsRawInt) Decode(buf []byte) { 1477 data := bytes.NewBuffer(buf) 1478 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 1479 binary.Read(data, binary.LittleEndian, &m.LAT) 1480 binary.Read(data, binary.LittleEndian, &m.LON) 1481 binary.Read(data, binary.LittleEndian, &m.ALT) 1482 binary.Read(data, binary.LittleEndian, &m.EPH) 1483 binary.Read(data, binary.LittleEndian, &m.EPV) 1484 binary.Read(data, binary.LittleEndian, &m.VEL) 1485 binary.Read(data, binary.LittleEndian, &m.COG) 1486 binary.Read(data, binary.LittleEndian, &m.FIX_TYPE) 1487 binary.Read(data, binary.LittleEndian, &m.SATELLITES_VISIBLE) 1488 } 1489 1490 // 1491 // MESSAGE GPS_STATUS 1492 // 1493 // MAVLINK_MSG_ID_GPS_STATUS 25 1494 // 1495 // MAVLINK_MSG_ID_GPS_STATUS_LEN 101 1496 // 1497 // MAVLINK_MSG_ID_GPS_STATUS_CRC 23 1498 // 1499 // 1500 type GpsStatus struct { 1501 SATELLITES_VISIBLE uint8 // Number of satellites visible 1502 SATELLITE_PRN [20]uint8 // Global satellite ID 1503 SATELLITE_USED [20]uint8 // 0: Satellite not used, 1: used for localization 1504 SATELLITE_ELEVATION [20]uint8 // Elevation (0: right on top of receiver, 90: on the horizon) of satellite 1505 SATELLITE_AZIMUTH [20]uint8 // Direction of satellite, 0: 0 deg, 255: 360 deg. 1506 SATELLITE_SNR [20]uint8 // Signal to noise ratio of satellite 1507 } 1508 1509 // NewGpsStatus returns a new GpsStatus 1510 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 { 1511 m := GpsStatus{} 1512 m.SATELLITES_VISIBLE = SATELLITES_VISIBLE 1513 m.SATELLITE_PRN = SATELLITE_PRN 1514 m.SATELLITE_USED = SATELLITE_USED 1515 m.SATELLITE_ELEVATION = SATELLITE_ELEVATION 1516 m.SATELLITE_AZIMUTH = SATELLITE_AZIMUTH 1517 m.SATELLITE_SNR = SATELLITE_SNR 1518 return &m 1519 } 1520 1521 // Id returns the GpsStatus Message ID 1522 func (*GpsStatus) Id() uint8 { 1523 return 25 1524 } 1525 1526 // Len returns the GpsStatus Message Length 1527 func (*GpsStatus) Len() uint8 { 1528 return 101 1529 } 1530 1531 // Crc returns the GpsStatus Message CRC 1532 func (*GpsStatus) Crc() uint8 { 1533 return 23 1534 } 1535 1536 // Pack returns a packed byte array which represents a GpsStatus payload 1537 func (m *GpsStatus) Pack() []byte { 1538 data := new(bytes.Buffer) 1539 binary.Write(data, binary.LittleEndian, m.SATELLITES_VISIBLE) 1540 binary.Write(data, binary.LittleEndian, m.SATELLITE_PRN) 1541 binary.Write(data, binary.LittleEndian, m.SATELLITE_USED) 1542 binary.Write(data, binary.LittleEndian, m.SATELLITE_ELEVATION) 1543 binary.Write(data, binary.LittleEndian, m.SATELLITE_AZIMUTH) 1544 binary.Write(data, binary.LittleEndian, m.SATELLITE_SNR) 1545 return data.Bytes() 1546 } 1547 1548 // Decode accepts a packed byte array and populates the fields of the GpsStatus 1549 func (m *GpsStatus) Decode(buf []byte) { 1550 data := bytes.NewBuffer(buf) 1551 binary.Read(data, binary.LittleEndian, &m.SATELLITES_VISIBLE) 1552 binary.Read(data, binary.LittleEndian, &m.SATELLITE_PRN) 1553 binary.Read(data, binary.LittleEndian, &m.SATELLITE_USED) 1554 binary.Read(data, binary.LittleEndian, &m.SATELLITE_ELEVATION) 1555 binary.Read(data, binary.LittleEndian, &m.SATELLITE_AZIMUTH) 1556 binary.Read(data, binary.LittleEndian, &m.SATELLITE_SNR) 1557 } 1558 1559 const ( 1560 MAVLINK_MSG_GPS_STATUS_FIELD_satellite_prn_LEN = 20 1561 MAVLINK_MSG_GPS_STATUS_FIELD_satellite_used_LEN = 20 1562 MAVLINK_MSG_GPS_STATUS_FIELD_satellite_elevation_LEN = 20 1563 MAVLINK_MSG_GPS_STATUS_FIELD_satellite_azimuth_LEN = 20 1564 MAVLINK_MSG_GPS_STATUS_FIELD_satellite_snr_LEN = 20 1565 ) 1566 1567 // 1568 // MESSAGE SCALED_IMU 1569 // 1570 // MAVLINK_MSG_ID_SCALED_IMU 26 1571 // 1572 // MAVLINK_MSG_ID_SCALED_IMU_LEN 22 1573 // 1574 // MAVLINK_MSG_ID_SCALED_IMU_CRC 170 1575 // 1576 // 1577 type ScaledImu struct { 1578 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 1579 XACC int16 // X acceleration (mg) 1580 YACC int16 // Y acceleration (mg) 1581 ZACC int16 // Z acceleration (mg) 1582 XGYRO int16 // Angular speed around X axis (millirad /sec) 1583 YGYRO int16 // Angular speed around Y axis (millirad /sec) 1584 ZGYRO int16 // Angular speed around Z axis (millirad /sec) 1585 XMAG int16 // X Magnetic field (milli tesla) 1586 YMAG int16 // Y Magnetic field (milli tesla) 1587 ZMAG int16 // Z Magnetic field (milli tesla) 1588 } 1589 1590 // NewScaledImu returns a new ScaledImu 1591 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 { 1592 m := ScaledImu{} 1593 m.TIME_BOOT_MS = TIME_BOOT_MS 1594 m.XACC = XACC 1595 m.YACC = YACC 1596 m.ZACC = ZACC 1597 m.XGYRO = XGYRO 1598 m.YGYRO = YGYRO 1599 m.ZGYRO = ZGYRO 1600 m.XMAG = XMAG 1601 m.YMAG = YMAG 1602 m.ZMAG = ZMAG 1603 return &m 1604 } 1605 1606 // Id returns the ScaledImu Message ID 1607 func (*ScaledImu) Id() uint8 { 1608 return 26 1609 } 1610 1611 // Len returns the ScaledImu Message Length 1612 func (*ScaledImu) Len() uint8 { 1613 return 22 1614 } 1615 1616 // Crc returns the ScaledImu Message CRC 1617 func (*ScaledImu) Crc() uint8 { 1618 return 170 1619 } 1620 1621 // Pack returns a packed byte array which represents a ScaledImu payload 1622 func (m *ScaledImu) Pack() []byte { 1623 data := new(bytes.Buffer) 1624 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 1625 binary.Write(data, binary.LittleEndian, m.XACC) 1626 binary.Write(data, binary.LittleEndian, m.YACC) 1627 binary.Write(data, binary.LittleEndian, m.ZACC) 1628 binary.Write(data, binary.LittleEndian, m.XGYRO) 1629 binary.Write(data, binary.LittleEndian, m.YGYRO) 1630 binary.Write(data, binary.LittleEndian, m.ZGYRO) 1631 binary.Write(data, binary.LittleEndian, m.XMAG) 1632 binary.Write(data, binary.LittleEndian, m.YMAG) 1633 binary.Write(data, binary.LittleEndian, m.ZMAG) 1634 return data.Bytes() 1635 } 1636 1637 // Decode accepts a packed byte array and populates the fields of the ScaledImu 1638 func (m *ScaledImu) Decode(buf []byte) { 1639 data := bytes.NewBuffer(buf) 1640 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 1641 binary.Read(data, binary.LittleEndian, &m.XACC) 1642 binary.Read(data, binary.LittleEndian, &m.YACC) 1643 binary.Read(data, binary.LittleEndian, &m.ZACC) 1644 binary.Read(data, binary.LittleEndian, &m.XGYRO) 1645 binary.Read(data, binary.LittleEndian, &m.YGYRO) 1646 binary.Read(data, binary.LittleEndian, &m.ZGYRO) 1647 binary.Read(data, binary.LittleEndian, &m.XMAG) 1648 binary.Read(data, binary.LittleEndian, &m.YMAG) 1649 binary.Read(data, binary.LittleEndian, &m.ZMAG) 1650 } 1651 1652 // 1653 // MESSAGE RAW_IMU 1654 // 1655 // MAVLINK_MSG_ID_RAW_IMU 27 1656 // 1657 // MAVLINK_MSG_ID_RAW_IMU_LEN 26 1658 // 1659 // MAVLINK_MSG_ID_RAW_IMU_CRC 144 1660 // 1661 // 1662 type RawImu struct { 1663 TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) 1664 XACC int16 // X acceleration (raw) 1665 YACC int16 // Y acceleration (raw) 1666 ZACC int16 // Z acceleration (raw) 1667 XGYRO int16 // Angular speed around X axis (raw) 1668 YGYRO int16 // Angular speed around Y axis (raw) 1669 ZGYRO int16 // Angular speed around Z axis (raw) 1670 XMAG int16 // X Magnetic field (raw) 1671 YMAG int16 // Y Magnetic field (raw) 1672 ZMAG int16 // Z Magnetic field (raw) 1673 } 1674 1675 // NewRawImu returns a new RawImu 1676 func NewRawImu(TIME_USEC uint64, XACC int16, YACC int16, ZACC int16, XGYRO int16, YGYRO int16, ZGYRO int16, XMAG int16, YMAG int16, ZMAG int16) *RawImu { 1677 m := RawImu{} 1678 m.TIME_USEC = TIME_USEC 1679 m.XACC = XACC 1680 m.YACC = YACC 1681 m.ZACC = ZACC 1682 m.XGYRO = XGYRO 1683 m.YGYRO = YGYRO 1684 m.ZGYRO = ZGYRO 1685 m.XMAG = XMAG 1686 m.YMAG = YMAG 1687 m.ZMAG = ZMAG 1688 return &m 1689 } 1690 1691 // Id returns the RawImu Message ID 1692 func (*RawImu) Id() uint8 { 1693 return 27 1694 } 1695 1696 // Len returns the RawImu Message Length 1697 func (*RawImu) Len() uint8 { 1698 return 26 1699 } 1700 1701 // Crc returns the RawImu Message CRC 1702 func (*RawImu) Crc() uint8 { 1703 return 144 1704 } 1705 1706 // Pack returns a packed byte array which represents a RawImu payload 1707 func (m *RawImu) Pack() []byte { 1708 data := new(bytes.Buffer) 1709 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 1710 binary.Write(data, binary.LittleEndian, m.XACC) 1711 binary.Write(data, binary.LittleEndian, m.YACC) 1712 binary.Write(data, binary.LittleEndian, m.ZACC) 1713 binary.Write(data, binary.LittleEndian, m.XGYRO) 1714 binary.Write(data, binary.LittleEndian, m.YGYRO) 1715 binary.Write(data, binary.LittleEndian, m.ZGYRO) 1716 binary.Write(data, binary.LittleEndian, m.XMAG) 1717 binary.Write(data, binary.LittleEndian, m.YMAG) 1718 binary.Write(data, binary.LittleEndian, m.ZMAG) 1719 return data.Bytes() 1720 } 1721 1722 // Decode accepts a packed byte array and populates the fields of the RawImu 1723 func (m *RawImu) Decode(buf []byte) { 1724 data := bytes.NewBuffer(buf) 1725 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 1726 binary.Read(data, binary.LittleEndian, &m.XACC) 1727 binary.Read(data, binary.LittleEndian, &m.YACC) 1728 binary.Read(data, binary.LittleEndian, &m.ZACC) 1729 binary.Read(data, binary.LittleEndian, &m.XGYRO) 1730 binary.Read(data, binary.LittleEndian, &m.YGYRO) 1731 binary.Read(data, binary.LittleEndian, &m.ZGYRO) 1732 binary.Read(data, binary.LittleEndian, &m.XMAG) 1733 binary.Read(data, binary.LittleEndian, &m.YMAG) 1734 binary.Read(data, binary.LittleEndian, &m.ZMAG) 1735 } 1736 1737 // 1738 // MESSAGE RAW_PRESSURE 1739 // 1740 // MAVLINK_MSG_ID_RAW_PRESSURE 28 1741 // 1742 // MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 1743 // 1744 // MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67 1745 // 1746 // 1747 type RawPressure struct { 1748 TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) 1749 PRESS_ABS int16 // Absolute pressure (raw) 1750 PRESS_DIFF1 int16 // Differential pressure 1 (raw) 1751 PRESS_DIFF2 int16 // Differential pressure 2 (raw) 1752 TEMPERATURE int16 // Raw Temperature measurement (raw) 1753 } 1754 1755 // NewRawPressure returns a new RawPressure 1756 func NewRawPressure(TIME_USEC uint64, PRESS_ABS int16, PRESS_DIFF1 int16, PRESS_DIFF2 int16, TEMPERATURE int16) *RawPressure { 1757 m := RawPressure{} 1758 m.TIME_USEC = TIME_USEC 1759 m.PRESS_ABS = PRESS_ABS 1760 m.PRESS_DIFF1 = PRESS_DIFF1 1761 m.PRESS_DIFF2 = PRESS_DIFF2 1762 m.TEMPERATURE = TEMPERATURE 1763 return &m 1764 } 1765 1766 // Id returns the RawPressure Message ID 1767 func (*RawPressure) Id() uint8 { 1768 return 28 1769 } 1770 1771 // Len returns the RawPressure Message Length 1772 func (*RawPressure) Len() uint8 { 1773 return 16 1774 } 1775 1776 // Crc returns the RawPressure Message CRC 1777 func (*RawPressure) Crc() uint8 { 1778 return 67 1779 } 1780 1781 // Pack returns a packed byte array which represents a RawPressure payload 1782 func (m *RawPressure) Pack() []byte { 1783 data := new(bytes.Buffer) 1784 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 1785 binary.Write(data, binary.LittleEndian, m.PRESS_ABS) 1786 binary.Write(data, binary.LittleEndian, m.PRESS_DIFF1) 1787 binary.Write(data, binary.LittleEndian, m.PRESS_DIFF2) 1788 binary.Write(data, binary.LittleEndian, m.TEMPERATURE) 1789 return data.Bytes() 1790 } 1791 1792 // Decode accepts a packed byte array and populates the fields of the RawPressure 1793 func (m *RawPressure) Decode(buf []byte) { 1794 data := bytes.NewBuffer(buf) 1795 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 1796 binary.Read(data, binary.LittleEndian, &m.PRESS_ABS) 1797 binary.Read(data, binary.LittleEndian, &m.PRESS_DIFF1) 1798 binary.Read(data, binary.LittleEndian, &m.PRESS_DIFF2) 1799 binary.Read(data, binary.LittleEndian, &m.TEMPERATURE) 1800 } 1801 1802 // 1803 // MESSAGE SCALED_PRESSURE 1804 // 1805 // MAVLINK_MSG_ID_SCALED_PRESSURE 29 1806 // 1807 // MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14 1808 // 1809 // MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115 1810 // 1811 // 1812 type ScaledPressure struct { 1813 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 1814 PRESS_ABS float32 // Absolute pressure (hectopascal) 1815 PRESS_DIFF float32 // Differential pressure 1 (hectopascal) 1816 TEMPERATURE int16 // Temperature measurement (0.01 degrees celsius) 1817 } 1818 1819 // NewScaledPressure returns a new ScaledPressure 1820 func NewScaledPressure(TIME_BOOT_MS uint32, PRESS_ABS float32, PRESS_DIFF float32, TEMPERATURE int16) *ScaledPressure { 1821 m := ScaledPressure{} 1822 m.TIME_BOOT_MS = TIME_BOOT_MS 1823 m.PRESS_ABS = PRESS_ABS 1824 m.PRESS_DIFF = PRESS_DIFF 1825 m.TEMPERATURE = TEMPERATURE 1826 return &m 1827 } 1828 1829 // Id returns the ScaledPressure Message ID 1830 func (*ScaledPressure) Id() uint8 { 1831 return 29 1832 } 1833 1834 // Len returns the ScaledPressure Message Length 1835 func (*ScaledPressure) Len() uint8 { 1836 return 14 1837 } 1838 1839 // Crc returns the ScaledPressure Message CRC 1840 func (*ScaledPressure) Crc() uint8 { 1841 return 115 1842 } 1843 1844 // Pack returns a packed byte array which represents a ScaledPressure payload 1845 func (m *ScaledPressure) Pack() []byte { 1846 data := new(bytes.Buffer) 1847 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 1848 binary.Write(data, binary.LittleEndian, m.PRESS_ABS) 1849 binary.Write(data, binary.LittleEndian, m.PRESS_DIFF) 1850 binary.Write(data, binary.LittleEndian, m.TEMPERATURE) 1851 return data.Bytes() 1852 } 1853 1854 // Decode accepts a packed byte array and populates the fields of the ScaledPressure 1855 func (m *ScaledPressure) Decode(buf []byte) { 1856 data := bytes.NewBuffer(buf) 1857 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 1858 binary.Read(data, binary.LittleEndian, &m.PRESS_ABS) 1859 binary.Read(data, binary.LittleEndian, &m.PRESS_DIFF) 1860 binary.Read(data, binary.LittleEndian, &m.TEMPERATURE) 1861 } 1862 1863 // 1864 // MESSAGE ATTITUDE 1865 // 1866 // MAVLINK_MSG_ID_ATTITUDE 30 1867 // 1868 // MAVLINK_MSG_ID_ATTITUDE_LEN 28 1869 // 1870 // MAVLINK_MSG_ID_ATTITUDE_CRC 39 1871 // 1872 // 1873 type Attitude struct { 1874 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 1875 ROLL float32 // Roll angle (rad, -pi..+pi) 1876 PITCH float32 // Pitch angle (rad, -pi..+pi) 1877 YAW float32 // Yaw angle (rad, -pi..+pi) 1878 ROLLSPEED float32 // Roll angular speed (rad/s) 1879 PITCHSPEED float32 // Pitch angular speed (rad/s) 1880 YAWSPEED float32 // Yaw angular speed (rad/s) 1881 } 1882 1883 // NewAttitude returns a new Attitude 1884 func NewAttitude(TIME_BOOT_MS uint32, ROLL float32, PITCH float32, YAW float32, ROLLSPEED float32, PITCHSPEED float32, YAWSPEED float32) *Attitude { 1885 m := Attitude{} 1886 m.TIME_BOOT_MS = TIME_BOOT_MS 1887 m.ROLL = ROLL 1888 m.PITCH = PITCH 1889 m.YAW = YAW 1890 m.ROLLSPEED = ROLLSPEED 1891 m.PITCHSPEED = PITCHSPEED 1892 m.YAWSPEED = YAWSPEED 1893 return &m 1894 } 1895 1896 // Id returns the Attitude Message ID 1897 func (*Attitude) Id() uint8 { 1898 return 30 1899 } 1900 1901 // Len returns the Attitude Message Length 1902 func (*Attitude) Len() uint8 { 1903 return 28 1904 } 1905 1906 // Crc returns the Attitude Message CRC 1907 func (*Attitude) Crc() uint8 { 1908 return 39 1909 } 1910 1911 // Pack returns a packed byte array which represents a Attitude payload 1912 func (m *Attitude) Pack() []byte { 1913 data := new(bytes.Buffer) 1914 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 1915 binary.Write(data, binary.LittleEndian, m.ROLL) 1916 binary.Write(data, binary.LittleEndian, m.PITCH) 1917 binary.Write(data, binary.LittleEndian, m.YAW) 1918 binary.Write(data, binary.LittleEndian, m.ROLLSPEED) 1919 binary.Write(data, binary.LittleEndian, m.PITCHSPEED) 1920 binary.Write(data, binary.LittleEndian, m.YAWSPEED) 1921 return data.Bytes() 1922 } 1923 1924 // Decode accepts a packed byte array and populates the fields of the Attitude 1925 func (m *Attitude) Decode(buf []byte) { 1926 data := bytes.NewBuffer(buf) 1927 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 1928 binary.Read(data, binary.LittleEndian, &m.ROLL) 1929 binary.Read(data, binary.LittleEndian, &m.PITCH) 1930 binary.Read(data, binary.LittleEndian, &m.YAW) 1931 binary.Read(data, binary.LittleEndian, &m.ROLLSPEED) 1932 binary.Read(data, binary.LittleEndian, &m.PITCHSPEED) 1933 binary.Read(data, binary.LittleEndian, &m.YAWSPEED) 1934 } 1935 1936 // 1937 // MESSAGE ATTITUDE_QUATERNION 1938 // 1939 // MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 1940 // 1941 // MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 1942 // 1943 // MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246 1944 // 1945 // 1946 type AttitudeQuaternion struct { 1947 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 1948 Q1 float32 // Quaternion component 1, w (1 in null-rotation) 1949 Q2 float32 // Quaternion component 2, x (0 in null-rotation) 1950 Q3 float32 // Quaternion component 3, y (0 in null-rotation) 1951 Q4 float32 // Quaternion component 4, z (0 in null-rotation) 1952 ROLLSPEED float32 // Roll angular speed (rad/s) 1953 PITCHSPEED float32 // Pitch angular speed (rad/s) 1954 YAWSPEED float32 // Yaw angular speed (rad/s) 1955 } 1956 1957 // NewAttitudeQuaternion returns a new AttitudeQuaternion 1958 func NewAttitudeQuaternion(TIME_BOOT_MS uint32, Q1 float32, Q2 float32, Q3 float32, Q4 float32, ROLLSPEED float32, PITCHSPEED float32, YAWSPEED float32) *AttitudeQuaternion { 1959 m := AttitudeQuaternion{} 1960 m.TIME_BOOT_MS = TIME_BOOT_MS 1961 m.Q1 = Q1 1962 m.Q2 = Q2 1963 m.Q3 = Q3 1964 m.Q4 = Q4 1965 m.ROLLSPEED = ROLLSPEED 1966 m.PITCHSPEED = PITCHSPEED 1967 m.YAWSPEED = YAWSPEED 1968 return &m 1969 } 1970 1971 // Id returns the AttitudeQuaternion Message ID 1972 func (*AttitudeQuaternion) Id() uint8 { 1973 return 31 1974 } 1975 1976 // Len returns the AttitudeQuaternion Message Length 1977 func (*AttitudeQuaternion) Len() uint8 { 1978 return 32 1979 } 1980 1981 // Crc returns the AttitudeQuaternion Message CRC 1982 func (*AttitudeQuaternion) Crc() uint8 { 1983 return 246 1984 } 1985 1986 // Pack returns a packed byte array which represents a AttitudeQuaternion payload 1987 func (m *AttitudeQuaternion) Pack() []byte { 1988 data := new(bytes.Buffer) 1989 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 1990 binary.Write(data, binary.LittleEndian, m.Q1) 1991 binary.Write(data, binary.LittleEndian, m.Q2) 1992 binary.Write(data, binary.LittleEndian, m.Q3) 1993 binary.Write(data, binary.LittleEndian, m.Q4) 1994 binary.Write(data, binary.LittleEndian, m.ROLLSPEED) 1995 binary.Write(data, binary.LittleEndian, m.PITCHSPEED) 1996 binary.Write(data, binary.LittleEndian, m.YAWSPEED) 1997 return data.Bytes() 1998 } 1999 2000 // Decode accepts a packed byte array and populates the fields of the AttitudeQuaternion 2001 func (m *AttitudeQuaternion) Decode(buf []byte) { 2002 data := bytes.NewBuffer(buf) 2003 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 2004 binary.Read(data, binary.LittleEndian, &m.Q1) 2005 binary.Read(data, binary.LittleEndian, &m.Q2) 2006 binary.Read(data, binary.LittleEndian, &m.Q3) 2007 binary.Read(data, binary.LittleEndian, &m.Q4) 2008 binary.Read(data, binary.LittleEndian, &m.ROLLSPEED) 2009 binary.Read(data, binary.LittleEndian, &m.PITCHSPEED) 2010 binary.Read(data, binary.LittleEndian, &m.YAWSPEED) 2011 } 2012 2013 // 2014 // MESSAGE LOCAL_POSITION_NED 2015 // 2016 // MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 2017 // 2018 // MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 2019 // 2020 // MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185 2021 // 2022 // 2023 type LocalPositionNed struct { 2024 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 2025 X float32 // X Position 2026 Y float32 // Y Position 2027 Z float32 // Z Position 2028 VX float32 // X Speed 2029 VY float32 // Y Speed 2030 VZ float32 // Z Speed 2031 } 2032 2033 // NewLocalPositionNed returns a new LocalPositionNed 2034 func NewLocalPositionNed(TIME_BOOT_MS uint32, X float32, Y float32, Z float32, VX float32, VY float32, VZ float32) *LocalPositionNed { 2035 m := LocalPositionNed{} 2036 m.TIME_BOOT_MS = TIME_BOOT_MS 2037 m.X = X 2038 m.Y = Y 2039 m.Z = Z 2040 m.VX = VX 2041 m.VY = VY 2042 m.VZ = VZ 2043 return &m 2044 } 2045 2046 // Id returns the LocalPositionNed Message ID 2047 func (*LocalPositionNed) Id() uint8 { 2048 return 32 2049 } 2050 2051 // Len returns the LocalPositionNed Message Length 2052 func (*LocalPositionNed) Len() uint8 { 2053 return 28 2054 } 2055 2056 // Crc returns the LocalPositionNed Message CRC 2057 func (*LocalPositionNed) Crc() uint8 { 2058 return 185 2059 } 2060 2061 // Pack returns a packed byte array which represents a LocalPositionNed payload 2062 func (m *LocalPositionNed) Pack() []byte { 2063 data := new(bytes.Buffer) 2064 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 2065 binary.Write(data, binary.LittleEndian, m.X) 2066 binary.Write(data, binary.LittleEndian, m.Y) 2067 binary.Write(data, binary.LittleEndian, m.Z) 2068 binary.Write(data, binary.LittleEndian, m.VX) 2069 binary.Write(data, binary.LittleEndian, m.VY) 2070 binary.Write(data, binary.LittleEndian, m.VZ) 2071 return data.Bytes() 2072 } 2073 2074 // Decode accepts a packed byte array and populates the fields of the LocalPositionNed 2075 func (m *LocalPositionNed) Decode(buf []byte) { 2076 data := bytes.NewBuffer(buf) 2077 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 2078 binary.Read(data, binary.LittleEndian, &m.X) 2079 binary.Read(data, binary.LittleEndian, &m.Y) 2080 binary.Read(data, binary.LittleEndian, &m.Z) 2081 binary.Read(data, binary.LittleEndian, &m.VX) 2082 binary.Read(data, binary.LittleEndian, &m.VY) 2083 binary.Read(data, binary.LittleEndian, &m.VZ) 2084 } 2085 2086 // 2087 // MESSAGE GLOBAL_POSITION_INT 2088 // 2089 // MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 2090 // 2091 // MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 2092 // 2093 // MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104 2094 // 2095 // 2096 type GlobalPositionInt struct { 2097 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 2098 LAT int32 // Latitude, expressed as * 1E7 2099 LON int32 // Longitude, expressed as * 1E7 2100 ALT int32 // Altitude in meters, expressed as * 1000 (millimeters), above MSL 2101 RELATIVE_ALT int32 // Altitude above ground in meters, expressed as * 1000 (millimeters) 2102 VX int16 // Ground X Speed (Latitude), expressed as m/s * 100 2103 VY int16 // Ground Y Speed (Longitude), expressed as m/s * 100 2104 VZ int16 // Ground Z Speed (Altitude), expressed as m/s * 100 2105 HDG uint16 // Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX 2106 } 2107 2108 // NewGlobalPositionInt returns a new GlobalPositionInt 2109 func NewGlobalPositionInt(TIME_BOOT_MS uint32, LAT int32, LON int32, ALT int32, RELATIVE_ALT int32, VX int16, VY int16, VZ int16, HDG uint16) *GlobalPositionInt { 2110 m := GlobalPositionInt{} 2111 m.TIME_BOOT_MS = TIME_BOOT_MS 2112 m.LAT = LAT 2113 m.LON = LON 2114 m.ALT = ALT 2115 m.RELATIVE_ALT = RELATIVE_ALT 2116 m.VX = VX 2117 m.VY = VY 2118 m.VZ = VZ 2119 m.HDG = HDG 2120 return &m 2121 } 2122 2123 // Id returns the GlobalPositionInt Message ID 2124 func (*GlobalPositionInt) Id() uint8 { 2125 return 33 2126 } 2127 2128 // Len returns the GlobalPositionInt Message Length 2129 func (*GlobalPositionInt) Len() uint8 { 2130 return 28 2131 } 2132 2133 // Crc returns the GlobalPositionInt Message CRC 2134 func (*GlobalPositionInt) Crc() uint8 { 2135 return 104 2136 } 2137 2138 // Pack returns a packed byte array which represents a GlobalPositionInt payload 2139 func (m *GlobalPositionInt) Pack() []byte { 2140 data := new(bytes.Buffer) 2141 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 2142 binary.Write(data, binary.LittleEndian, m.LAT) 2143 binary.Write(data, binary.LittleEndian, m.LON) 2144 binary.Write(data, binary.LittleEndian, m.ALT) 2145 binary.Write(data, binary.LittleEndian, m.RELATIVE_ALT) 2146 binary.Write(data, binary.LittleEndian, m.VX) 2147 binary.Write(data, binary.LittleEndian, m.VY) 2148 binary.Write(data, binary.LittleEndian, m.VZ) 2149 binary.Write(data, binary.LittleEndian, m.HDG) 2150 return data.Bytes() 2151 } 2152 2153 // Decode accepts a packed byte array and populates the fields of the GlobalPositionInt 2154 func (m *GlobalPositionInt) Decode(buf []byte) { 2155 data := bytes.NewBuffer(buf) 2156 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 2157 binary.Read(data, binary.LittleEndian, &m.LAT) 2158 binary.Read(data, binary.LittleEndian, &m.LON) 2159 binary.Read(data, binary.LittleEndian, &m.ALT) 2160 binary.Read(data, binary.LittleEndian, &m.RELATIVE_ALT) 2161 binary.Read(data, binary.LittleEndian, &m.VX) 2162 binary.Read(data, binary.LittleEndian, &m.VY) 2163 binary.Read(data, binary.LittleEndian, &m.VZ) 2164 binary.Read(data, binary.LittleEndian, &m.HDG) 2165 } 2166 2167 // 2168 // MESSAGE RC_CHANNELS_SCALED 2169 // 2170 // MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34 2171 // 2172 // MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 2173 // 2174 // MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237 2175 // 2176 // 2177 type RcChannelsScaled struct { 2178 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 2179 CHAN1_SCALED int16 // RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. 2180 CHAN2_SCALED int16 // RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. 2181 CHAN3_SCALED int16 // RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. 2182 CHAN4_SCALED int16 // RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. 2183 CHAN5_SCALED int16 // RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. 2184 CHAN6_SCALED int16 // RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. 2185 CHAN7_SCALED int16 // RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. 2186 CHAN8_SCALED int16 // RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. 2187 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. 2188 RSSI uint8 // Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. 2189 } 2190 2191 // NewRcChannelsScaled returns a new RcChannelsScaled 2192 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 { 2193 m := RcChannelsScaled{} 2194 m.TIME_BOOT_MS = TIME_BOOT_MS 2195 m.CHAN1_SCALED = CHAN1_SCALED 2196 m.CHAN2_SCALED = CHAN2_SCALED 2197 m.CHAN3_SCALED = CHAN3_SCALED 2198 m.CHAN4_SCALED = CHAN4_SCALED 2199 m.CHAN5_SCALED = CHAN5_SCALED 2200 m.CHAN6_SCALED = CHAN6_SCALED 2201 m.CHAN7_SCALED = CHAN7_SCALED 2202 m.CHAN8_SCALED = CHAN8_SCALED 2203 m.PORT = PORT 2204 m.RSSI = RSSI 2205 return &m 2206 } 2207 2208 // Id returns the RcChannelsScaled Message ID 2209 func (*RcChannelsScaled) Id() uint8 { 2210 return 34 2211 } 2212 2213 // Len returns the RcChannelsScaled Message Length 2214 func (*RcChannelsScaled) Len() uint8 { 2215 return 22 2216 } 2217 2218 // Crc returns the RcChannelsScaled Message CRC 2219 func (*RcChannelsScaled) Crc() uint8 { 2220 return 237 2221 } 2222 2223 // Pack returns a packed byte array which represents a RcChannelsScaled payload 2224 func (m *RcChannelsScaled) Pack() []byte { 2225 data := new(bytes.Buffer) 2226 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 2227 binary.Write(data, binary.LittleEndian, m.CHAN1_SCALED) 2228 binary.Write(data, binary.LittleEndian, m.CHAN2_SCALED) 2229 binary.Write(data, binary.LittleEndian, m.CHAN3_SCALED) 2230 binary.Write(data, binary.LittleEndian, m.CHAN4_SCALED) 2231 binary.Write(data, binary.LittleEndian, m.CHAN5_SCALED) 2232 binary.Write(data, binary.LittleEndian, m.CHAN6_SCALED) 2233 binary.Write(data, binary.LittleEndian, m.CHAN7_SCALED) 2234 binary.Write(data, binary.LittleEndian, m.CHAN8_SCALED) 2235 binary.Write(data, binary.LittleEndian, m.PORT) 2236 binary.Write(data, binary.LittleEndian, m.RSSI) 2237 return data.Bytes() 2238 } 2239 2240 // Decode accepts a packed byte array and populates the fields of the RcChannelsScaled 2241 func (m *RcChannelsScaled) Decode(buf []byte) { 2242 data := bytes.NewBuffer(buf) 2243 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 2244 binary.Read(data, binary.LittleEndian, &m.CHAN1_SCALED) 2245 binary.Read(data, binary.LittleEndian, &m.CHAN2_SCALED) 2246 binary.Read(data, binary.LittleEndian, &m.CHAN3_SCALED) 2247 binary.Read(data, binary.LittleEndian, &m.CHAN4_SCALED) 2248 binary.Read(data, binary.LittleEndian, &m.CHAN5_SCALED) 2249 binary.Read(data, binary.LittleEndian, &m.CHAN6_SCALED) 2250 binary.Read(data, binary.LittleEndian, &m.CHAN7_SCALED) 2251 binary.Read(data, binary.LittleEndian, &m.CHAN8_SCALED) 2252 binary.Read(data, binary.LittleEndian, &m.PORT) 2253 binary.Read(data, binary.LittleEndian, &m.RSSI) 2254 } 2255 2256 // 2257 // MESSAGE RC_CHANNELS_RAW 2258 // 2259 // MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 2260 // 2261 // MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 2262 // 2263 // MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244 2264 // 2265 // 2266 type RcChannelsRaw struct { 2267 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 2268 CHAN1_RAW uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 2269 CHAN2_RAW uint16 // RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 2270 CHAN3_RAW uint16 // RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 2271 CHAN4_RAW uint16 // RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 2272 CHAN5_RAW uint16 // RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 2273 CHAN6_RAW uint16 // RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 2274 CHAN7_RAW uint16 // RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 2275 CHAN8_RAW uint16 // RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 2276 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. 2277 RSSI uint8 // Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. 2278 } 2279 2280 // NewRcChannelsRaw returns a new RcChannelsRaw 2281 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 { 2282 m := RcChannelsRaw{} 2283 m.TIME_BOOT_MS = TIME_BOOT_MS 2284 m.CHAN1_RAW = CHAN1_RAW 2285 m.CHAN2_RAW = CHAN2_RAW 2286 m.CHAN3_RAW = CHAN3_RAW 2287 m.CHAN4_RAW = CHAN4_RAW 2288 m.CHAN5_RAW = CHAN5_RAW 2289 m.CHAN6_RAW = CHAN6_RAW 2290 m.CHAN7_RAW = CHAN7_RAW 2291 m.CHAN8_RAW = CHAN8_RAW 2292 m.PORT = PORT 2293 m.RSSI = RSSI 2294 return &m 2295 } 2296 2297 // Id returns the RcChannelsRaw Message ID 2298 func (*RcChannelsRaw) Id() uint8 { 2299 return 35 2300 } 2301 2302 // Len returns the RcChannelsRaw Message Length 2303 func (*RcChannelsRaw) Len() uint8 { 2304 return 22 2305 } 2306 2307 // Crc returns the RcChannelsRaw Message CRC 2308 func (*RcChannelsRaw) Crc() uint8 { 2309 return 244 2310 } 2311 2312 // Pack returns a packed byte array which represents a RcChannelsRaw payload 2313 func (m *RcChannelsRaw) Pack() []byte { 2314 data := new(bytes.Buffer) 2315 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 2316 binary.Write(data, binary.LittleEndian, m.CHAN1_RAW) 2317 binary.Write(data, binary.LittleEndian, m.CHAN2_RAW) 2318 binary.Write(data, binary.LittleEndian, m.CHAN3_RAW) 2319 binary.Write(data, binary.LittleEndian, m.CHAN4_RAW) 2320 binary.Write(data, binary.LittleEndian, m.CHAN5_RAW) 2321 binary.Write(data, binary.LittleEndian, m.CHAN6_RAW) 2322 binary.Write(data, binary.LittleEndian, m.CHAN7_RAW) 2323 binary.Write(data, binary.LittleEndian, m.CHAN8_RAW) 2324 binary.Write(data, binary.LittleEndian, m.PORT) 2325 binary.Write(data, binary.LittleEndian, m.RSSI) 2326 return data.Bytes() 2327 } 2328 2329 // Decode accepts a packed byte array and populates the fields of the RcChannelsRaw 2330 func (m *RcChannelsRaw) Decode(buf []byte) { 2331 data := bytes.NewBuffer(buf) 2332 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 2333 binary.Read(data, binary.LittleEndian, &m.CHAN1_RAW) 2334 binary.Read(data, binary.LittleEndian, &m.CHAN2_RAW) 2335 binary.Read(data, binary.LittleEndian, &m.CHAN3_RAW) 2336 binary.Read(data, binary.LittleEndian, &m.CHAN4_RAW) 2337 binary.Read(data, binary.LittleEndian, &m.CHAN5_RAW) 2338 binary.Read(data, binary.LittleEndian, &m.CHAN6_RAW) 2339 binary.Read(data, binary.LittleEndian, &m.CHAN7_RAW) 2340 binary.Read(data, binary.LittleEndian, &m.CHAN8_RAW) 2341 binary.Read(data, binary.LittleEndian, &m.PORT) 2342 binary.Read(data, binary.LittleEndian, &m.RSSI) 2343 } 2344 2345 // 2346 // MESSAGE SERVO_OUTPUT_RAW 2347 // 2348 // MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36 2349 // 2350 // MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21 2351 // 2352 // MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC 222 2353 // 2354 // 2355 type ServoOutputRaw struct { 2356 TIME_USEC uint32 // Timestamp (microseconds since system boot) 2357 SERVO1_RAW uint16 // Servo output 1 value, in microseconds 2358 SERVO2_RAW uint16 // Servo output 2 value, in microseconds 2359 SERVO3_RAW uint16 // Servo output 3 value, in microseconds 2360 SERVO4_RAW uint16 // Servo output 4 value, in microseconds 2361 SERVO5_RAW uint16 // Servo output 5 value, in microseconds 2362 SERVO6_RAW uint16 // Servo output 6 value, in microseconds 2363 SERVO7_RAW uint16 // Servo output 7 value, in microseconds 2364 SERVO8_RAW uint16 // Servo output 8 value, in microseconds 2365 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. 2366 } 2367 2368 // NewServoOutputRaw returns a new ServoOutputRaw 2369 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 { 2370 m := ServoOutputRaw{} 2371 m.TIME_USEC = TIME_USEC 2372 m.SERVO1_RAW = SERVO1_RAW 2373 m.SERVO2_RAW = SERVO2_RAW 2374 m.SERVO3_RAW = SERVO3_RAW 2375 m.SERVO4_RAW = SERVO4_RAW 2376 m.SERVO5_RAW = SERVO5_RAW 2377 m.SERVO6_RAW = SERVO6_RAW 2378 m.SERVO7_RAW = SERVO7_RAW 2379 m.SERVO8_RAW = SERVO8_RAW 2380 m.PORT = PORT 2381 return &m 2382 } 2383 2384 // Id returns the ServoOutputRaw Message ID 2385 func (*ServoOutputRaw) Id() uint8 { 2386 return 36 2387 } 2388 2389 // Len returns the ServoOutputRaw Message Length 2390 func (*ServoOutputRaw) Len() uint8 { 2391 return 21 2392 } 2393 2394 // Crc returns the ServoOutputRaw Message CRC 2395 func (*ServoOutputRaw) Crc() uint8 { 2396 return 222 2397 } 2398 2399 // Pack returns a packed byte array which represents a ServoOutputRaw payload 2400 func (m *ServoOutputRaw) Pack() []byte { 2401 data := new(bytes.Buffer) 2402 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 2403 binary.Write(data, binary.LittleEndian, m.SERVO1_RAW) 2404 binary.Write(data, binary.LittleEndian, m.SERVO2_RAW) 2405 binary.Write(data, binary.LittleEndian, m.SERVO3_RAW) 2406 binary.Write(data, binary.LittleEndian, m.SERVO4_RAW) 2407 binary.Write(data, binary.LittleEndian, m.SERVO5_RAW) 2408 binary.Write(data, binary.LittleEndian, m.SERVO6_RAW) 2409 binary.Write(data, binary.LittleEndian, m.SERVO7_RAW) 2410 binary.Write(data, binary.LittleEndian, m.SERVO8_RAW) 2411 binary.Write(data, binary.LittleEndian, m.PORT) 2412 return data.Bytes() 2413 } 2414 2415 // Decode accepts a packed byte array and populates the fields of the ServoOutputRaw 2416 func (m *ServoOutputRaw) Decode(buf []byte) { 2417 data := bytes.NewBuffer(buf) 2418 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 2419 binary.Read(data, binary.LittleEndian, &m.SERVO1_RAW) 2420 binary.Read(data, binary.LittleEndian, &m.SERVO2_RAW) 2421 binary.Read(data, binary.LittleEndian, &m.SERVO3_RAW) 2422 binary.Read(data, binary.LittleEndian, &m.SERVO4_RAW) 2423 binary.Read(data, binary.LittleEndian, &m.SERVO5_RAW) 2424 binary.Read(data, binary.LittleEndian, &m.SERVO6_RAW) 2425 binary.Read(data, binary.LittleEndian, &m.SERVO7_RAW) 2426 binary.Read(data, binary.LittleEndian, &m.SERVO8_RAW) 2427 binary.Read(data, binary.LittleEndian, &m.PORT) 2428 } 2429 2430 // 2431 // MESSAGE MISSION_REQUEST_PARTIAL_LIST 2432 // 2433 // MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37 2434 // 2435 // MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6 2436 // 2437 // MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212 2438 // 2439 // 2440 type MissionRequestPartialList struct { 2441 START_INDEX int16 // Start index, 0 by default 2442 END_INDEX int16 // End index, -1 by default (-1: send list to end). Else a valid index of the list 2443 TARGET_SYSTEM uint8 // System ID 2444 TARGET_COMPONENT uint8 // Component ID 2445 } 2446 2447 // NewMissionRequestPartialList returns a new MissionRequestPartialList 2448 func NewMissionRequestPartialList(START_INDEX int16, END_INDEX int16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionRequestPartialList { 2449 m := MissionRequestPartialList{} 2450 m.START_INDEX = START_INDEX 2451 m.END_INDEX = END_INDEX 2452 m.TARGET_SYSTEM = TARGET_SYSTEM 2453 m.TARGET_COMPONENT = TARGET_COMPONENT 2454 return &m 2455 } 2456 2457 // Id returns the MissionRequestPartialList Message ID 2458 func (*MissionRequestPartialList) Id() uint8 { 2459 return 37 2460 } 2461 2462 // Len returns the MissionRequestPartialList Message Length 2463 func (*MissionRequestPartialList) Len() uint8 { 2464 return 6 2465 } 2466 2467 // Crc returns the MissionRequestPartialList Message CRC 2468 func (*MissionRequestPartialList) Crc() uint8 { 2469 return 212 2470 } 2471 2472 // Pack returns a packed byte array which represents a MissionRequestPartialList payload 2473 func (m *MissionRequestPartialList) Pack() []byte { 2474 data := new(bytes.Buffer) 2475 binary.Write(data, binary.LittleEndian, m.START_INDEX) 2476 binary.Write(data, binary.LittleEndian, m.END_INDEX) 2477 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 2478 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 2479 return data.Bytes() 2480 } 2481 2482 // Decode accepts a packed byte array and populates the fields of the MissionRequestPartialList 2483 func (m *MissionRequestPartialList) Decode(buf []byte) { 2484 data := bytes.NewBuffer(buf) 2485 binary.Read(data, binary.LittleEndian, &m.START_INDEX) 2486 binary.Read(data, binary.LittleEndian, &m.END_INDEX) 2487 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 2488 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 2489 } 2490 2491 // 2492 // MESSAGE MISSION_WRITE_PARTIAL_LIST 2493 // 2494 // MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38 2495 // 2496 // MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6 2497 // 2498 // MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9 2499 // 2500 // 2501 type MissionWritePartialList struct { 2502 START_INDEX int16 // Start index, 0 by default and smaller / equal to the largest index of the current onboard list. 2503 END_INDEX int16 // End index, equal or greater than start index. 2504 TARGET_SYSTEM uint8 // System ID 2505 TARGET_COMPONENT uint8 // Component ID 2506 } 2507 2508 // NewMissionWritePartialList returns a new MissionWritePartialList 2509 func NewMissionWritePartialList(START_INDEX int16, END_INDEX int16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionWritePartialList { 2510 m := MissionWritePartialList{} 2511 m.START_INDEX = START_INDEX 2512 m.END_INDEX = END_INDEX 2513 m.TARGET_SYSTEM = TARGET_SYSTEM 2514 m.TARGET_COMPONENT = TARGET_COMPONENT 2515 return &m 2516 } 2517 2518 // Id returns the MissionWritePartialList Message ID 2519 func (*MissionWritePartialList) Id() uint8 { 2520 return 38 2521 } 2522 2523 // Len returns the MissionWritePartialList Message Length 2524 func (*MissionWritePartialList) Len() uint8 { 2525 return 6 2526 } 2527 2528 // Crc returns the MissionWritePartialList Message CRC 2529 func (*MissionWritePartialList) Crc() uint8 { 2530 return 9 2531 } 2532 2533 // Pack returns a packed byte array which represents a MissionWritePartialList payload 2534 func (m *MissionWritePartialList) Pack() []byte { 2535 data := new(bytes.Buffer) 2536 binary.Write(data, binary.LittleEndian, m.START_INDEX) 2537 binary.Write(data, binary.LittleEndian, m.END_INDEX) 2538 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 2539 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 2540 return data.Bytes() 2541 } 2542 2543 // Decode accepts a packed byte array and populates the fields of the MissionWritePartialList 2544 func (m *MissionWritePartialList) Decode(buf []byte) { 2545 data := bytes.NewBuffer(buf) 2546 binary.Read(data, binary.LittleEndian, &m.START_INDEX) 2547 binary.Read(data, binary.LittleEndian, &m.END_INDEX) 2548 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 2549 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 2550 } 2551 2552 // 2553 // MESSAGE MISSION_ITEM 2554 // 2555 // MAVLINK_MSG_ID_MISSION_ITEM 39 2556 // 2557 // MAVLINK_MSG_ID_MISSION_ITEM_LEN 37 2558 // 2559 // MAVLINK_MSG_ID_MISSION_ITEM_CRC 254 2560 // 2561 // 2562 type MissionItem struct { 2563 PARAM1 float32 // PARAM1, see MAV_CMD enum 2564 PARAM2 float32 // PARAM2, see MAV_CMD enum 2565 PARAM3 float32 // PARAM3, see MAV_CMD enum 2566 PARAM4 float32 // PARAM4, see MAV_CMD enum 2567 X float32 // PARAM5 / local: x position, global: latitude 2568 Y float32 // PARAM6 / y position: global: longitude 2569 Z float32 // PARAM7 / z position: global: altitude (relative or absolute, depending on frame. 2570 SEQ uint16 // Sequence 2571 COMMAND uint16 // The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs 2572 TARGET_SYSTEM uint8 // System ID 2573 TARGET_COMPONENT uint8 // Component ID 2574 FRAME uint8 // The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h 2575 CURRENT uint8 // false:0, true:1 2576 AUTOCONTINUE uint8 // autocontinue to next wp 2577 } 2578 2579 // NewMissionItem returns a new MissionItem 2580 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 { 2581 m := MissionItem{} 2582 m.PARAM1 = PARAM1 2583 m.PARAM2 = PARAM2 2584 m.PARAM3 = PARAM3 2585 m.PARAM4 = PARAM4 2586 m.X = X 2587 m.Y = Y 2588 m.Z = Z 2589 m.SEQ = SEQ 2590 m.COMMAND = COMMAND 2591 m.TARGET_SYSTEM = TARGET_SYSTEM 2592 m.TARGET_COMPONENT = TARGET_COMPONENT 2593 m.FRAME = FRAME 2594 m.CURRENT = CURRENT 2595 m.AUTOCONTINUE = AUTOCONTINUE 2596 return &m 2597 } 2598 2599 // Id returns the MissionItem Message ID 2600 func (*MissionItem) Id() uint8 { 2601 return 39 2602 } 2603 2604 // Len returns the MissionItem Message Length 2605 func (*MissionItem) Len() uint8 { 2606 return 37 2607 } 2608 2609 // Crc returns the MissionItem Message CRC 2610 func (*MissionItem) Crc() uint8 { 2611 return 254 2612 } 2613 2614 // Pack returns a packed byte array which represents a MissionItem payload 2615 func (m *MissionItem) Pack() []byte { 2616 data := new(bytes.Buffer) 2617 binary.Write(data, binary.LittleEndian, m.PARAM1) 2618 binary.Write(data, binary.LittleEndian, m.PARAM2) 2619 binary.Write(data, binary.LittleEndian, m.PARAM3) 2620 binary.Write(data, binary.LittleEndian, m.PARAM4) 2621 binary.Write(data, binary.LittleEndian, m.X) 2622 binary.Write(data, binary.LittleEndian, m.Y) 2623 binary.Write(data, binary.LittleEndian, m.Z) 2624 binary.Write(data, binary.LittleEndian, m.SEQ) 2625 binary.Write(data, binary.LittleEndian, m.COMMAND) 2626 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 2627 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 2628 binary.Write(data, binary.LittleEndian, m.FRAME) 2629 binary.Write(data, binary.LittleEndian, m.CURRENT) 2630 binary.Write(data, binary.LittleEndian, m.AUTOCONTINUE) 2631 return data.Bytes() 2632 } 2633 2634 // Decode accepts a packed byte array and populates the fields of the MissionItem 2635 func (m *MissionItem) Decode(buf []byte) { 2636 data := bytes.NewBuffer(buf) 2637 binary.Read(data, binary.LittleEndian, &m.PARAM1) 2638 binary.Read(data, binary.LittleEndian, &m.PARAM2) 2639 binary.Read(data, binary.LittleEndian, &m.PARAM3) 2640 binary.Read(data, binary.LittleEndian, &m.PARAM4) 2641 binary.Read(data, binary.LittleEndian, &m.X) 2642 binary.Read(data, binary.LittleEndian, &m.Y) 2643 binary.Read(data, binary.LittleEndian, &m.Z) 2644 binary.Read(data, binary.LittleEndian, &m.SEQ) 2645 binary.Read(data, binary.LittleEndian, &m.COMMAND) 2646 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 2647 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 2648 binary.Read(data, binary.LittleEndian, &m.FRAME) 2649 binary.Read(data, binary.LittleEndian, &m.CURRENT) 2650 binary.Read(data, binary.LittleEndian, &m.AUTOCONTINUE) 2651 } 2652 2653 // 2654 // MESSAGE MISSION_REQUEST 2655 // 2656 // MAVLINK_MSG_ID_MISSION_REQUEST 40 2657 // 2658 // MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4 2659 // 2660 // MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230 2661 // 2662 // 2663 type MissionRequest struct { 2664 SEQ uint16 // Sequence 2665 TARGET_SYSTEM uint8 // System ID 2666 TARGET_COMPONENT uint8 // Component ID 2667 } 2668 2669 // NewMissionRequest returns a new MissionRequest 2670 func NewMissionRequest(SEQ uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionRequest { 2671 m := MissionRequest{} 2672 m.SEQ = SEQ 2673 m.TARGET_SYSTEM = TARGET_SYSTEM 2674 m.TARGET_COMPONENT = TARGET_COMPONENT 2675 return &m 2676 } 2677 2678 // Id returns the MissionRequest Message ID 2679 func (*MissionRequest) Id() uint8 { 2680 return 40 2681 } 2682 2683 // Len returns the MissionRequest Message Length 2684 func (*MissionRequest) Len() uint8 { 2685 return 4 2686 } 2687 2688 // Crc returns the MissionRequest Message CRC 2689 func (*MissionRequest) Crc() uint8 { 2690 return 230 2691 } 2692 2693 // Pack returns a packed byte array which represents a MissionRequest payload 2694 func (m *MissionRequest) Pack() []byte { 2695 data := new(bytes.Buffer) 2696 binary.Write(data, binary.LittleEndian, m.SEQ) 2697 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 2698 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 2699 return data.Bytes() 2700 } 2701 2702 // Decode accepts a packed byte array and populates the fields of the MissionRequest 2703 func (m *MissionRequest) Decode(buf []byte) { 2704 data := bytes.NewBuffer(buf) 2705 binary.Read(data, binary.LittleEndian, &m.SEQ) 2706 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 2707 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 2708 } 2709 2710 // 2711 // MESSAGE MISSION_SET_CURRENT 2712 // 2713 // MAVLINK_MSG_ID_MISSION_SET_CURRENT 41 2714 // 2715 // MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 2716 // 2717 // MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC 28 2718 // 2719 // 2720 type MissionSetCurrent struct { 2721 SEQ uint16 // Sequence 2722 TARGET_SYSTEM uint8 // System ID 2723 TARGET_COMPONENT uint8 // Component ID 2724 } 2725 2726 // NewMissionSetCurrent returns a new MissionSetCurrent 2727 func NewMissionSetCurrent(SEQ uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionSetCurrent { 2728 m := MissionSetCurrent{} 2729 m.SEQ = SEQ 2730 m.TARGET_SYSTEM = TARGET_SYSTEM 2731 m.TARGET_COMPONENT = TARGET_COMPONENT 2732 return &m 2733 } 2734 2735 // Id returns the MissionSetCurrent Message ID 2736 func (*MissionSetCurrent) Id() uint8 { 2737 return 41 2738 } 2739 2740 // Len returns the MissionSetCurrent Message Length 2741 func (*MissionSetCurrent) Len() uint8 { 2742 return 4 2743 } 2744 2745 // Crc returns the MissionSetCurrent Message CRC 2746 func (*MissionSetCurrent) Crc() uint8 { 2747 return 28 2748 } 2749 2750 // Pack returns a packed byte array which represents a MissionSetCurrent payload 2751 func (m *MissionSetCurrent) Pack() []byte { 2752 data := new(bytes.Buffer) 2753 binary.Write(data, binary.LittleEndian, m.SEQ) 2754 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 2755 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 2756 return data.Bytes() 2757 } 2758 2759 // Decode accepts a packed byte array and populates the fields of the MissionSetCurrent 2760 func (m *MissionSetCurrent) Decode(buf []byte) { 2761 data := bytes.NewBuffer(buf) 2762 binary.Read(data, binary.LittleEndian, &m.SEQ) 2763 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 2764 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 2765 } 2766 2767 // 2768 // MESSAGE MISSION_CURRENT 2769 // 2770 // MAVLINK_MSG_ID_MISSION_CURRENT 42 2771 // 2772 // MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2 2773 // 2774 // MAVLINK_MSG_ID_MISSION_CURRENT_CRC 28 2775 // 2776 // 2777 type MissionCurrent struct { 2778 SEQ uint16 // Sequence 2779 } 2780 2781 // NewMissionCurrent returns a new MissionCurrent 2782 func NewMissionCurrent(SEQ uint16) *MissionCurrent { 2783 m := MissionCurrent{} 2784 m.SEQ = SEQ 2785 return &m 2786 } 2787 2788 // Id returns the MissionCurrent Message ID 2789 func (*MissionCurrent) Id() uint8 { 2790 return 42 2791 } 2792 2793 // Len returns the MissionCurrent Message Length 2794 func (*MissionCurrent) Len() uint8 { 2795 return 2 2796 } 2797 2798 // Crc returns the MissionCurrent Message CRC 2799 func (*MissionCurrent) Crc() uint8 { 2800 return 28 2801 } 2802 2803 // Pack returns a packed byte array which represents a MissionCurrent payload 2804 func (m *MissionCurrent) Pack() []byte { 2805 data := new(bytes.Buffer) 2806 binary.Write(data, binary.LittleEndian, m.SEQ) 2807 return data.Bytes() 2808 } 2809 2810 // Decode accepts a packed byte array and populates the fields of the MissionCurrent 2811 func (m *MissionCurrent) Decode(buf []byte) { 2812 data := bytes.NewBuffer(buf) 2813 binary.Read(data, binary.LittleEndian, &m.SEQ) 2814 } 2815 2816 // 2817 // MESSAGE MISSION_REQUEST_LIST 2818 // 2819 // MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43 2820 // 2821 // MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2 2822 // 2823 // MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC 132 2824 // 2825 // 2826 type MissionRequestList struct { 2827 TARGET_SYSTEM uint8 // System ID 2828 TARGET_COMPONENT uint8 // Component ID 2829 } 2830 2831 // NewMissionRequestList returns a new MissionRequestList 2832 func NewMissionRequestList(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionRequestList { 2833 m := MissionRequestList{} 2834 m.TARGET_SYSTEM = TARGET_SYSTEM 2835 m.TARGET_COMPONENT = TARGET_COMPONENT 2836 return &m 2837 } 2838 2839 // Id returns the MissionRequestList Message ID 2840 func (*MissionRequestList) Id() uint8 { 2841 return 43 2842 } 2843 2844 // Len returns the MissionRequestList Message Length 2845 func (*MissionRequestList) Len() uint8 { 2846 return 2 2847 } 2848 2849 // Crc returns the MissionRequestList Message CRC 2850 func (*MissionRequestList) Crc() uint8 { 2851 return 132 2852 } 2853 2854 // Pack returns a packed byte array which represents a MissionRequestList payload 2855 func (m *MissionRequestList) Pack() []byte { 2856 data := new(bytes.Buffer) 2857 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 2858 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 2859 return data.Bytes() 2860 } 2861 2862 // Decode accepts a packed byte array and populates the fields of the MissionRequestList 2863 func (m *MissionRequestList) Decode(buf []byte) { 2864 data := bytes.NewBuffer(buf) 2865 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 2866 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 2867 } 2868 2869 // 2870 // MESSAGE MISSION_COUNT 2871 // 2872 // MAVLINK_MSG_ID_MISSION_COUNT 44 2873 // 2874 // MAVLINK_MSG_ID_MISSION_COUNT_LEN 4 2875 // 2876 // MAVLINK_MSG_ID_MISSION_COUNT_CRC 221 2877 // 2878 // 2879 type MissionCount struct { 2880 COUNT uint16 // Number of mission items in the sequence 2881 TARGET_SYSTEM uint8 // System ID 2882 TARGET_COMPONENT uint8 // Component ID 2883 } 2884 2885 // NewMissionCount returns a new MissionCount 2886 func NewMissionCount(COUNT uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionCount { 2887 m := MissionCount{} 2888 m.COUNT = COUNT 2889 m.TARGET_SYSTEM = TARGET_SYSTEM 2890 m.TARGET_COMPONENT = TARGET_COMPONENT 2891 return &m 2892 } 2893 2894 // Id returns the MissionCount Message ID 2895 func (*MissionCount) Id() uint8 { 2896 return 44 2897 } 2898 2899 // Len returns the MissionCount Message Length 2900 func (*MissionCount) Len() uint8 { 2901 return 4 2902 } 2903 2904 // Crc returns the MissionCount Message CRC 2905 func (*MissionCount) Crc() uint8 { 2906 return 221 2907 } 2908 2909 // Pack returns a packed byte array which represents a MissionCount payload 2910 func (m *MissionCount) Pack() []byte { 2911 data := new(bytes.Buffer) 2912 binary.Write(data, binary.LittleEndian, m.COUNT) 2913 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 2914 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 2915 return data.Bytes() 2916 } 2917 2918 // Decode accepts a packed byte array and populates the fields of the MissionCount 2919 func (m *MissionCount) Decode(buf []byte) { 2920 data := bytes.NewBuffer(buf) 2921 binary.Read(data, binary.LittleEndian, &m.COUNT) 2922 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 2923 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 2924 } 2925 2926 // 2927 // MESSAGE MISSION_CLEAR_ALL 2928 // 2929 // MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45 2930 // 2931 // MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2 2932 // 2933 // MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC 232 2934 // 2935 // 2936 type MissionClearAll struct { 2937 TARGET_SYSTEM uint8 // System ID 2938 TARGET_COMPONENT uint8 // Component ID 2939 } 2940 2941 // NewMissionClearAll returns a new MissionClearAll 2942 func NewMissionClearAll(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *MissionClearAll { 2943 m := MissionClearAll{} 2944 m.TARGET_SYSTEM = TARGET_SYSTEM 2945 m.TARGET_COMPONENT = TARGET_COMPONENT 2946 return &m 2947 } 2948 2949 // Id returns the MissionClearAll Message ID 2950 func (*MissionClearAll) Id() uint8 { 2951 return 45 2952 } 2953 2954 // Len returns the MissionClearAll Message Length 2955 func (*MissionClearAll) Len() uint8 { 2956 return 2 2957 } 2958 2959 // Crc returns the MissionClearAll Message CRC 2960 func (*MissionClearAll) Crc() uint8 { 2961 return 232 2962 } 2963 2964 // Pack returns a packed byte array which represents a MissionClearAll payload 2965 func (m *MissionClearAll) Pack() []byte { 2966 data := new(bytes.Buffer) 2967 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 2968 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 2969 return data.Bytes() 2970 } 2971 2972 // Decode accepts a packed byte array and populates the fields of the MissionClearAll 2973 func (m *MissionClearAll) Decode(buf []byte) { 2974 data := bytes.NewBuffer(buf) 2975 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 2976 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 2977 } 2978 2979 // 2980 // MESSAGE MISSION_ITEM_REACHED 2981 // 2982 // MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46 2983 // 2984 // MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 2985 // 2986 // MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC 11 2987 // 2988 // 2989 type MissionItemReached struct { 2990 SEQ uint16 // Sequence 2991 } 2992 2993 // NewMissionItemReached returns a new MissionItemReached 2994 func NewMissionItemReached(SEQ uint16) *MissionItemReached { 2995 m := MissionItemReached{} 2996 m.SEQ = SEQ 2997 return &m 2998 } 2999 3000 // Id returns the MissionItemReached Message ID 3001 func (*MissionItemReached) Id() uint8 { 3002 return 46 3003 } 3004 3005 // Len returns the MissionItemReached Message Length 3006 func (*MissionItemReached) Len() uint8 { 3007 return 2 3008 } 3009 3010 // Crc returns the MissionItemReached Message CRC 3011 func (*MissionItemReached) Crc() uint8 { 3012 return 11 3013 } 3014 3015 // Pack returns a packed byte array which represents a MissionItemReached payload 3016 func (m *MissionItemReached) Pack() []byte { 3017 data := new(bytes.Buffer) 3018 binary.Write(data, binary.LittleEndian, m.SEQ) 3019 return data.Bytes() 3020 } 3021 3022 // Decode accepts a packed byte array and populates the fields of the MissionItemReached 3023 func (m *MissionItemReached) Decode(buf []byte) { 3024 data := bytes.NewBuffer(buf) 3025 binary.Read(data, binary.LittleEndian, &m.SEQ) 3026 } 3027 3028 // 3029 // MESSAGE MISSION_ACK 3030 // 3031 // MAVLINK_MSG_ID_MISSION_ACK 47 3032 // 3033 // MAVLINK_MSG_ID_MISSION_ACK_LEN 3 3034 // 3035 // MAVLINK_MSG_ID_MISSION_ACK_CRC 153 3036 // 3037 // 3038 type MissionAck struct { 3039 TARGET_SYSTEM uint8 // System ID 3040 TARGET_COMPONENT uint8 // Component ID 3041 TYPE uint8 // See MAV_MISSION_RESULT enum 3042 } 3043 3044 // NewMissionAck returns a new MissionAck 3045 func NewMissionAck(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, TYPE uint8) *MissionAck { 3046 m := MissionAck{} 3047 m.TARGET_SYSTEM = TARGET_SYSTEM 3048 m.TARGET_COMPONENT = TARGET_COMPONENT 3049 m.TYPE = TYPE 3050 return &m 3051 } 3052 3053 // Id returns the MissionAck Message ID 3054 func (*MissionAck) Id() uint8 { 3055 return 47 3056 } 3057 3058 // Len returns the MissionAck Message Length 3059 func (*MissionAck) Len() uint8 { 3060 return 3 3061 } 3062 3063 // Crc returns the MissionAck Message CRC 3064 func (*MissionAck) Crc() uint8 { 3065 return 153 3066 } 3067 3068 // Pack returns a packed byte array which represents a MissionAck payload 3069 func (m *MissionAck) Pack() []byte { 3070 data := new(bytes.Buffer) 3071 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 3072 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 3073 binary.Write(data, binary.LittleEndian, m.TYPE) 3074 return data.Bytes() 3075 } 3076 3077 // Decode accepts a packed byte array and populates the fields of the MissionAck 3078 func (m *MissionAck) Decode(buf []byte) { 3079 data := bytes.NewBuffer(buf) 3080 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 3081 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 3082 binary.Read(data, binary.LittleEndian, &m.TYPE) 3083 } 3084 3085 // 3086 // MESSAGE SET_GPS_GLOBAL_ORIGIN 3087 // 3088 // MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48 3089 // 3090 // MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13 3091 // 3092 // MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC 41 3093 // 3094 // 3095 type SetGpsGlobalOrigin struct { 3096 LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 3097 LONGITUDE int32 // Longitude (WGS84, in degrees * 1E7 3098 ALTITUDE int32 // Altitude (WGS84), in meters * 1000 (positive for up) 3099 TARGET_SYSTEM uint8 // System ID 3100 } 3101 3102 // NewSetGpsGlobalOrigin returns a new SetGpsGlobalOrigin 3103 func NewSetGpsGlobalOrigin(LATITUDE int32, LONGITUDE int32, ALTITUDE int32, TARGET_SYSTEM uint8) *SetGpsGlobalOrigin { 3104 m := SetGpsGlobalOrigin{} 3105 m.LATITUDE = LATITUDE 3106 m.LONGITUDE = LONGITUDE 3107 m.ALTITUDE = ALTITUDE 3108 m.TARGET_SYSTEM = TARGET_SYSTEM 3109 return &m 3110 } 3111 3112 // Id returns the SetGpsGlobalOrigin Message ID 3113 func (*SetGpsGlobalOrigin) Id() uint8 { 3114 return 48 3115 } 3116 3117 // Len returns the SetGpsGlobalOrigin Message Length 3118 func (*SetGpsGlobalOrigin) Len() uint8 { 3119 return 13 3120 } 3121 3122 // Crc returns the SetGpsGlobalOrigin Message CRC 3123 func (*SetGpsGlobalOrigin) Crc() uint8 { 3124 return 41 3125 } 3126 3127 // Pack returns a packed byte array which represents a SetGpsGlobalOrigin payload 3128 func (m *SetGpsGlobalOrigin) Pack() []byte { 3129 data := new(bytes.Buffer) 3130 binary.Write(data, binary.LittleEndian, m.LATITUDE) 3131 binary.Write(data, binary.LittleEndian, m.LONGITUDE) 3132 binary.Write(data, binary.LittleEndian, m.ALTITUDE) 3133 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 3134 return data.Bytes() 3135 } 3136 3137 // Decode accepts a packed byte array and populates the fields of the SetGpsGlobalOrigin 3138 func (m *SetGpsGlobalOrigin) Decode(buf []byte) { 3139 data := bytes.NewBuffer(buf) 3140 binary.Read(data, binary.LittleEndian, &m.LATITUDE) 3141 binary.Read(data, binary.LittleEndian, &m.LONGITUDE) 3142 binary.Read(data, binary.LittleEndian, &m.ALTITUDE) 3143 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 3144 } 3145 3146 // 3147 // MESSAGE GPS_GLOBAL_ORIGIN 3148 // 3149 // MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 3150 // 3151 // MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 3152 // 3153 // MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39 3154 // 3155 // 3156 type GpsGlobalOrigin struct { 3157 LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 3158 LONGITUDE int32 // Longitude (WGS84), in degrees * 1E7 3159 ALTITUDE int32 // Altitude (WGS84), in meters * 1000 (positive for up) 3160 } 3161 3162 // NewGpsGlobalOrigin returns a new GpsGlobalOrigin 3163 func NewGpsGlobalOrigin(LATITUDE int32, LONGITUDE int32, ALTITUDE int32) *GpsGlobalOrigin { 3164 m := GpsGlobalOrigin{} 3165 m.LATITUDE = LATITUDE 3166 m.LONGITUDE = LONGITUDE 3167 m.ALTITUDE = ALTITUDE 3168 return &m 3169 } 3170 3171 // Id returns the GpsGlobalOrigin Message ID 3172 func (*GpsGlobalOrigin) Id() uint8 { 3173 return 49 3174 } 3175 3176 // Len returns the GpsGlobalOrigin Message Length 3177 func (*GpsGlobalOrigin) Len() uint8 { 3178 return 12 3179 } 3180 3181 // Crc returns the GpsGlobalOrigin Message CRC 3182 func (*GpsGlobalOrigin) Crc() uint8 { 3183 return 39 3184 } 3185 3186 // Pack returns a packed byte array which represents a GpsGlobalOrigin payload 3187 func (m *GpsGlobalOrigin) Pack() []byte { 3188 data := new(bytes.Buffer) 3189 binary.Write(data, binary.LittleEndian, m.LATITUDE) 3190 binary.Write(data, binary.LittleEndian, m.LONGITUDE) 3191 binary.Write(data, binary.LittleEndian, m.ALTITUDE) 3192 return data.Bytes() 3193 } 3194 3195 // Decode accepts a packed byte array and populates the fields of the GpsGlobalOrigin 3196 func (m *GpsGlobalOrigin) Decode(buf []byte) { 3197 data := bytes.NewBuffer(buf) 3198 binary.Read(data, binary.LittleEndian, &m.LATITUDE) 3199 binary.Read(data, binary.LittleEndian, &m.LONGITUDE) 3200 binary.Read(data, binary.LittleEndian, &m.ALTITUDE) 3201 } 3202 3203 // 3204 // MESSAGE SET_LOCAL_POSITION_SETPOINT 3205 // 3206 // MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT 50 3207 // 3208 // MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN 19 3209 // 3210 // MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC 214 3211 // 3212 // 3213 type SetLocalPositionSetpoint struct { 3214 X float32 // x position 3215 Y float32 // y position 3216 Z float32 // z position 3217 YAW float32 // Desired yaw angle 3218 TARGET_SYSTEM uint8 // System ID 3219 TARGET_COMPONENT uint8 // Component ID 3220 COORDINATE_FRAME uint8 // Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU 3221 } 3222 3223 // NewSetLocalPositionSetpoint returns a new SetLocalPositionSetpoint 3224 func NewSetLocalPositionSetpoint(X float32, Y float32, Z float32, YAW float32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, COORDINATE_FRAME uint8) *SetLocalPositionSetpoint { 3225 m := SetLocalPositionSetpoint{} 3226 m.X = X 3227 m.Y = Y 3228 m.Z = Z 3229 m.YAW = YAW 3230 m.TARGET_SYSTEM = TARGET_SYSTEM 3231 m.TARGET_COMPONENT = TARGET_COMPONENT 3232 m.COORDINATE_FRAME = COORDINATE_FRAME 3233 return &m 3234 } 3235 3236 // Id returns the SetLocalPositionSetpoint Message ID 3237 func (*SetLocalPositionSetpoint) Id() uint8 { 3238 return 50 3239 } 3240 3241 // Len returns the SetLocalPositionSetpoint Message Length 3242 func (*SetLocalPositionSetpoint) Len() uint8 { 3243 return 19 3244 } 3245 3246 // Crc returns the SetLocalPositionSetpoint Message CRC 3247 func (*SetLocalPositionSetpoint) Crc() uint8 { 3248 return 214 3249 } 3250 3251 // Pack returns a packed byte array which represents a SetLocalPositionSetpoint payload 3252 func (m *SetLocalPositionSetpoint) Pack() []byte { 3253 data := new(bytes.Buffer) 3254 binary.Write(data, binary.LittleEndian, m.X) 3255 binary.Write(data, binary.LittleEndian, m.Y) 3256 binary.Write(data, binary.LittleEndian, m.Z) 3257 binary.Write(data, binary.LittleEndian, m.YAW) 3258 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 3259 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 3260 binary.Write(data, binary.LittleEndian, m.COORDINATE_FRAME) 3261 return data.Bytes() 3262 } 3263 3264 // Decode accepts a packed byte array and populates the fields of the SetLocalPositionSetpoint 3265 func (m *SetLocalPositionSetpoint) Decode(buf []byte) { 3266 data := bytes.NewBuffer(buf) 3267 binary.Read(data, binary.LittleEndian, &m.X) 3268 binary.Read(data, binary.LittleEndian, &m.Y) 3269 binary.Read(data, binary.LittleEndian, &m.Z) 3270 binary.Read(data, binary.LittleEndian, &m.YAW) 3271 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 3272 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 3273 binary.Read(data, binary.LittleEndian, &m.COORDINATE_FRAME) 3274 } 3275 3276 // 3277 // MESSAGE LOCAL_POSITION_SETPOINT 3278 // 3279 // MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51 3280 // 3281 // MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 17 3282 // 3283 // MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC 223 3284 // 3285 // 3286 type LocalPositionSetpoint struct { 3287 X float32 // x position 3288 Y float32 // y position 3289 Z float32 // z position 3290 YAW float32 // Desired yaw angle 3291 COORDINATE_FRAME uint8 // Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU 3292 } 3293 3294 // NewLocalPositionSetpoint returns a new LocalPositionSetpoint 3295 func NewLocalPositionSetpoint(X float32, Y float32, Z float32, YAW float32, COORDINATE_FRAME uint8) *LocalPositionSetpoint { 3296 m := LocalPositionSetpoint{} 3297 m.X = X 3298 m.Y = Y 3299 m.Z = Z 3300 m.YAW = YAW 3301 m.COORDINATE_FRAME = COORDINATE_FRAME 3302 return &m 3303 } 3304 3305 // Id returns the LocalPositionSetpoint Message ID 3306 func (*LocalPositionSetpoint) Id() uint8 { 3307 return 51 3308 } 3309 3310 // Len returns the LocalPositionSetpoint Message Length 3311 func (*LocalPositionSetpoint) Len() uint8 { 3312 return 17 3313 } 3314 3315 // Crc returns the LocalPositionSetpoint Message CRC 3316 func (*LocalPositionSetpoint) Crc() uint8 { 3317 return 223 3318 } 3319 3320 // Pack returns a packed byte array which represents a LocalPositionSetpoint payload 3321 func (m *LocalPositionSetpoint) Pack() []byte { 3322 data := new(bytes.Buffer) 3323 binary.Write(data, binary.LittleEndian, m.X) 3324 binary.Write(data, binary.LittleEndian, m.Y) 3325 binary.Write(data, binary.LittleEndian, m.Z) 3326 binary.Write(data, binary.LittleEndian, m.YAW) 3327 binary.Write(data, binary.LittleEndian, m.COORDINATE_FRAME) 3328 return data.Bytes() 3329 } 3330 3331 // Decode accepts a packed byte array and populates the fields of the LocalPositionSetpoint 3332 func (m *LocalPositionSetpoint) Decode(buf []byte) { 3333 data := bytes.NewBuffer(buf) 3334 binary.Read(data, binary.LittleEndian, &m.X) 3335 binary.Read(data, binary.LittleEndian, &m.Y) 3336 binary.Read(data, binary.LittleEndian, &m.Z) 3337 binary.Read(data, binary.LittleEndian, &m.YAW) 3338 binary.Read(data, binary.LittleEndian, &m.COORDINATE_FRAME) 3339 } 3340 3341 // 3342 // MESSAGE GLOBAL_POSITION_SETPOINT_INT 3343 // 3344 // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT 52 3345 // 3346 // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 15 3347 // 3348 // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC 141 3349 // 3350 // 3351 type GlobalPositionSetpointInt struct { 3352 LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 3353 LONGITUDE int32 // Longitude (WGS84), in degrees * 1E7 3354 ALTITUDE int32 // Altitude (WGS84), in meters * 1000 (positive for up) 3355 YAW int16 // Desired yaw angle in degrees * 100 3356 COORDINATE_FRAME uint8 // Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT 3357 } 3358 3359 // NewGlobalPositionSetpointInt returns a new GlobalPositionSetpointInt 3360 func NewGlobalPositionSetpointInt(LATITUDE int32, LONGITUDE int32, ALTITUDE int32, YAW int16, COORDINATE_FRAME uint8) *GlobalPositionSetpointInt { 3361 m := GlobalPositionSetpointInt{} 3362 m.LATITUDE = LATITUDE 3363 m.LONGITUDE = LONGITUDE 3364 m.ALTITUDE = ALTITUDE 3365 m.YAW = YAW 3366 m.COORDINATE_FRAME = COORDINATE_FRAME 3367 return &m 3368 } 3369 3370 // Id returns the GlobalPositionSetpointInt Message ID 3371 func (*GlobalPositionSetpointInt) Id() uint8 { 3372 return 52 3373 } 3374 3375 // Len returns the GlobalPositionSetpointInt Message Length 3376 func (*GlobalPositionSetpointInt) Len() uint8 { 3377 return 15 3378 } 3379 3380 // Crc returns the GlobalPositionSetpointInt Message CRC 3381 func (*GlobalPositionSetpointInt) Crc() uint8 { 3382 return 141 3383 } 3384 3385 // Pack returns a packed byte array which represents a GlobalPositionSetpointInt payload 3386 func (m *GlobalPositionSetpointInt) Pack() []byte { 3387 data := new(bytes.Buffer) 3388 binary.Write(data, binary.LittleEndian, m.LATITUDE) 3389 binary.Write(data, binary.LittleEndian, m.LONGITUDE) 3390 binary.Write(data, binary.LittleEndian, m.ALTITUDE) 3391 binary.Write(data, binary.LittleEndian, m.YAW) 3392 binary.Write(data, binary.LittleEndian, m.COORDINATE_FRAME) 3393 return data.Bytes() 3394 } 3395 3396 // Decode accepts a packed byte array and populates the fields of the GlobalPositionSetpointInt 3397 func (m *GlobalPositionSetpointInt) Decode(buf []byte) { 3398 data := bytes.NewBuffer(buf) 3399 binary.Read(data, binary.LittleEndian, &m.LATITUDE) 3400 binary.Read(data, binary.LittleEndian, &m.LONGITUDE) 3401 binary.Read(data, binary.LittleEndian, &m.ALTITUDE) 3402 binary.Read(data, binary.LittleEndian, &m.YAW) 3403 binary.Read(data, binary.LittleEndian, &m.COORDINATE_FRAME) 3404 } 3405 3406 // 3407 // MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT 3408 // 3409 // MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT 53 3410 // 3411 // MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN 15 3412 // 3413 // MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC 33 3414 // 3415 // 3416 type SetGlobalPositionSetpointInt struct { 3417 LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 3418 LONGITUDE int32 // Longitude (WGS84), in degrees * 1E7 3419 ALTITUDE int32 // Altitude (WGS84), in meters * 1000 (positive for up) 3420 YAW int16 // Desired yaw angle in degrees * 100 3421 COORDINATE_FRAME uint8 // Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT 3422 } 3423 3424 // NewSetGlobalPositionSetpointInt returns a new SetGlobalPositionSetpointInt 3425 func NewSetGlobalPositionSetpointInt(LATITUDE int32, LONGITUDE int32, ALTITUDE int32, YAW int16, COORDINATE_FRAME uint8) *SetGlobalPositionSetpointInt { 3426 m := SetGlobalPositionSetpointInt{} 3427 m.LATITUDE = LATITUDE 3428 m.LONGITUDE = LONGITUDE 3429 m.ALTITUDE = ALTITUDE 3430 m.YAW = YAW 3431 m.COORDINATE_FRAME = COORDINATE_FRAME 3432 return &m 3433 } 3434 3435 // Id returns the SetGlobalPositionSetpointInt Message ID 3436 func (*SetGlobalPositionSetpointInt) Id() uint8 { 3437 return 53 3438 } 3439 3440 // Len returns the SetGlobalPositionSetpointInt Message Length 3441 func (*SetGlobalPositionSetpointInt) Len() uint8 { 3442 return 15 3443 } 3444 3445 // Crc returns the SetGlobalPositionSetpointInt Message CRC 3446 func (*SetGlobalPositionSetpointInt) Crc() uint8 { 3447 return 33 3448 } 3449 3450 // Pack returns a packed byte array which represents a SetGlobalPositionSetpointInt payload 3451 func (m *SetGlobalPositionSetpointInt) Pack() []byte { 3452 data := new(bytes.Buffer) 3453 binary.Write(data, binary.LittleEndian, m.LATITUDE) 3454 binary.Write(data, binary.LittleEndian, m.LONGITUDE) 3455 binary.Write(data, binary.LittleEndian, m.ALTITUDE) 3456 binary.Write(data, binary.LittleEndian, m.YAW) 3457 binary.Write(data, binary.LittleEndian, m.COORDINATE_FRAME) 3458 return data.Bytes() 3459 } 3460 3461 // Decode accepts a packed byte array and populates the fields of the SetGlobalPositionSetpointInt 3462 func (m *SetGlobalPositionSetpointInt) Decode(buf []byte) { 3463 data := bytes.NewBuffer(buf) 3464 binary.Read(data, binary.LittleEndian, &m.LATITUDE) 3465 binary.Read(data, binary.LittleEndian, &m.LONGITUDE) 3466 binary.Read(data, binary.LittleEndian, &m.ALTITUDE) 3467 binary.Read(data, binary.LittleEndian, &m.YAW) 3468 binary.Read(data, binary.LittleEndian, &m.COORDINATE_FRAME) 3469 } 3470 3471 // 3472 // MESSAGE SAFETY_SET_ALLOWED_AREA 3473 // 3474 // MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 3475 // 3476 // MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 3477 // 3478 // MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15 3479 // 3480 // 3481 type SafetySetAllowedArea struct { 3482 P1X float32 // x position 1 / Latitude 1 3483 P1Y float32 // y position 1 / Longitude 1 3484 P1Z float32 // z position 1 / Altitude 1 3485 P2X float32 // x position 2 / Latitude 2 3486 P2Y float32 // y position 2 / Longitude 2 3487 P2Z float32 // z position 2 / Altitude 2 3488 TARGET_SYSTEM uint8 // System ID 3489 TARGET_COMPONENT uint8 // Component ID 3490 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. 3491 } 3492 3493 // NewSafetySetAllowedArea returns a new SafetySetAllowedArea 3494 func NewSafetySetAllowedArea(P1X float32, P1Y float32, P1Z float32, P2X float32, P2Y float32, P2Z float32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, FRAME uint8) *SafetySetAllowedArea { 3495 m := SafetySetAllowedArea{} 3496 m.P1X = P1X 3497 m.P1Y = P1Y 3498 m.P1Z = P1Z 3499 m.P2X = P2X 3500 m.P2Y = P2Y 3501 m.P2Z = P2Z 3502 m.TARGET_SYSTEM = TARGET_SYSTEM 3503 m.TARGET_COMPONENT = TARGET_COMPONENT 3504 m.FRAME = FRAME 3505 return &m 3506 } 3507 3508 // Id returns the SafetySetAllowedArea Message ID 3509 func (*SafetySetAllowedArea) Id() uint8 { 3510 return 54 3511 } 3512 3513 // Len returns the SafetySetAllowedArea Message Length 3514 func (*SafetySetAllowedArea) Len() uint8 { 3515 return 27 3516 } 3517 3518 // Crc returns the SafetySetAllowedArea Message CRC 3519 func (*SafetySetAllowedArea) Crc() uint8 { 3520 return 15 3521 } 3522 3523 // Pack returns a packed byte array which represents a SafetySetAllowedArea payload 3524 func (m *SafetySetAllowedArea) Pack() []byte { 3525 data := new(bytes.Buffer) 3526 binary.Write(data, binary.LittleEndian, m.P1X) 3527 binary.Write(data, binary.LittleEndian, m.P1Y) 3528 binary.Write(data, binary.LittleEndian, m.P1Z) 3529 binary.Write(data, binary.LittleEndian, m.P2X) 3530 binary.Write(data, binary.LittleEndian, m.P2Y) 3531 binary.Write(data, binary.LittleEndian, m.P2Z) 3532 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 3533 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 3534 binary.Write(data, binary.LittleEndian, m.FRAME) 3535 return data.Bytes() 3536 } 3537 3538 // Decode accepts a packed byte array and populates the fields of the SafetySetAllowedArea 3539 func (m *SafetySetAllowedArea) Decode(buf []byte) { 3540 data := bytes.NewBuffer(buf) 3541 binary.Read(data, binary.LittleEndian, &m.P1X) 3542 binary.Read(data, binary.LittleEndian, &m.P1Y) 3543 binary.Read(data, binary.LittleEndian, &m.P1Z) 3544 binary.Read(data, binary.LittleEndian, &m.P2X) 3545 binary.Read(data, binary.LittleEndian, &m.P2Y) 3546 binary.Read(data, binary.LittleEndian, &m.P2Z) 3547 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 3548 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 3549 binary.Read(data, binary.LittleEndian, &m.FRAME) 3550 } 3551 3552 // 3553 // MESSAGE SAFETY_ALLOWED_AREA 3554 // 3555 // MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 3556 // 3557 // MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 3558 // 3559 // MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3 3560 // 3561 // 3562 type SafetyAllowedArea struct { 3563 P1X float32 // x position 1 / Latitude 1 3564 P1Y float32 // y position 1 / Longitude 1 3565 P1Z float32 // z position 1 / Altitude 1 3566 P2X float32 // x position 2 / Latitude 2 3567 P2Y float32 // y position 2 / Longitude 2 3568 P2Z float32 // z position 2 / Altitude 2 3569 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. 3570 } 3571 3572 // NewSafetyAllowedArea returns a new SafetyAllowedArea 3573 func NewSafetyAllowedArea(P1X float32, P1Y float32, P1Z float32, P2X float32, P2Y float32, P2Z float32, FRAME uint8) *SafetyAllowedArea { 3574 m := SafetyAllowedArea{} 3575 m.P1X = P1X 3576 m.P1Y = P1Y 3577 m.P1Z = P1Z 3578 m.P2X = P2X 3579 m.P2Y = P2Y 3580 m.P2Z = P2Z 3581 m.FRAME = FRAME 3582 return &m 3583 } 3584 3585 // Id returns the SafetyAllowedArea Message ID 3586 func (*SafetyAllowedArea) Id() uint8 { 3587 return 55 3588 } 3589 3590 // Len returns the SafetyAllowedArea Message Length 3591 func (*SafetyAllowedArea) Len() uint8 { 3592 return 25 3593 } 3594 3595 // Crc returns the SafetyAllowedArea Message CRC 3596 func (*SafetyAllowedArea) Crc() uint8 { 3597 return 3 3598 } 3599 3600 // Pack returns a packed byte array which represents a SafetyAllowedArea payload 3601 func (m *SafetyAllowedArea) Pack() []byte { 3602 data := new(bytes.Buffer) 3603 binary.Write(data, binary.LittleEndian, m.P1X) 3604 binary.Write(data, binary.LittleEndian, m.P1Y) 3605 binary.Write(data, binary.LittleEndian, m.P1Z) 3606 binary.Write(data, binary.LittleEndian, m.P2X) 3607 binary.Write(data, binary.LittleEndian, m.P2Y) 3608 binary.Write(data, binary.LittleEndian, m.P2Z) 3609 binary.Write(data, binary.LittleEndian, m.FRAME) 3610 return data.Bytes() 3611 } 3612 3613 // Decode accepts a packed byte array and populates the fields of the SafetyAllowedArea 3614 func (m *SafetyAllowedArea) Decode(buf []byte) { 3615 data := bytes.NewBuffer(buf) 3616 binary.Read(data, binary.LittleEndian, &m.P1X) 3617 binary.Read(data, binary.LittleEndian, &m.P1Y) 3618 binary.Read(data, binary.LittleEndian, &m.P1Z) 3619 binary.Read(data, binary.LittleEndian, &m.P2X) 3620 binary.Read(data, binary.LittleEndian, &m.P2Y) 3621 binary.Read(data, binary.LittleEndian, &m.P2Z) 3622 binary.Read(data, binary.LittleEndian, &m.FRAME) 3623 } 3624 3625 // 3626 // MESSAGE SET_ROLL_PITCH_YAW_THRUST 3627 // 3628 // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST 56 3629 // 3630 // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN 18 3631 // 3632 // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC 100 3633 // 3634 // 3635 type SetRollPitchYawThrust struct { 3636 ROLL float32 // Desired roll angle in radians 3637 PITCH float32 // Desired pitch angle in radians 3638 YAW float32 // Desired yaw angle in radians 3639 THRUST float32 // Collective thrust, normalized to 0 .. 1 3640 TARGET_SYSTEM uint8 // System ID 3641 TARGET_COMPONENT uint8 // Component ID 3642 } 3643 3644 // NewSetRollPitchYawThrust returns a new SetRollPitchYawThrust 3645 func NewSetRollPitchYawThrust(ROLL float32, PITCH float32, YAW float32, THRUST float32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *SetRollPitchYawThrust { 3646 m := SetRollPitchYawThrust{} 3647 m.ROLL = ROLL 3648 m.PITCH = PITCH 3649 m.YAW = YAW 3650 m.THRUST = THRUST 3651 m.TARGET_SYSTEM = TARGET_SYSTEM 3652 m.TARGET_COMPONENT = TARGET_COMPONENT 3653 return &m 3654 } 3655 3656 // Id returns the SetRollPitchYawThrust Message ID 3657 func (*SetRollPitchYawThrust) Id() uint8 { 3658 return 56 3659 } 3660 3661 // Len returns the SetRollPitchYawThrust Message Length 3662 func (*SetRollPitchYawThrust) Len() uint8 { 3663 return 18 3664 } 3665 3666 // Crc returns the SetRollPitchYawThrust Message CRC 3667 func (*SetRollPitchYawThrust) Crc() uint8 { 3668 return 100 3669 } 3670 3671 // Pack returns a packed byte array which represents a SetRollPitchYawThrust payload 3672 func (m *SetRollPitchYawThrust) Pack() []byte { 3673 data := new(bytes.Buffer) 3674 binary.Write(data, binary.LittleEndian, m.ROLL) 3675 binary.Write(data, binary.LittleEndian, m.PITCH) 3676 binary.Write(data, binary.LittleEndian, m.YAW) 3677 binary.Write(data, binary.LittleEndian, m.THRUST) 3678 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 3679 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 3680 return data.Bytes() 3681 } 3682 3683 // Decode accepts a packed byte array and populates the fields of the SetRollPitchYawThrust 3684 func (m *SetRollPitchYawThrust) Decode(buf []byte) { 3685 data := bytes.NewBuffer(buf) 3686 binary.Read(data, binary.LittleEndian, &m.ROLL) 3687 binary.Read(data, binary.LittleEndian, &m.PITCH) 3688 binary.Read(data, binary.LittleEndian, &m.YAW) 3689 binary.Read(data, binary.LittleEndian, &m.THRUST) 3690 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 3691 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 3692 } 3693 3694 // 3695 // MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST 3696 // 3697 // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST 57 3698 // 3699 // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN 18 3700 // 3701 // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC 24 3702 // 3703 // 3704 type SetRollPitchYawSpeedThrust struct { 3705 ROLL_SPEED float32 // Desired roll angular speed in rad/s 3706 PITCH_SPEED float32 // Desired pitch angular speed in rad/s 3707 YAW_SPEED float32 // Desired yaw angular speed in rad/s 3708 THRUST float32 // Collective thrust, normalized to 0 .. 1 3709 TARGET_SYSTEM uint8 // System ID 3710 TARGET_COMPONENT uint8 // Component ID 3711 } 3712 3713 // NewSetRollPitchYawSpeedThrust returns a new SetRollPitchYawSpeedThrust 3714 func NewSetRollPitchYawSpeedThrust(ROLL_SPEED float32, PITCH_SPEED float32, YAW_SPEED float32, THRUST float32, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *SetRollPitchYawSpeedThrust { 3715 m := SetRollPitchYawSpeedThrust{} 3716 m.ROLL_SPEED = ROLL_SPEED 3717 m.PITCH_SPEED = PITCH_SPEED 3718 m.YAW_SPEED = YAW_SPEED 3719 m.THRUST = THRUST 3720 m.TARGET_SYSTEM = TARGET_SYSTEM 3721 m.TARGET_COMPONENT = TARGET_COMPONENT 3722 return &m 3723 } 3724 3725 // Id returns the SetRollPitchYawSpeedThrust Message ID 3726 func (*SetRollPitchYawSpeedThrust) Id() uint8 { 3727 return 57 3728 } 3729 3730 // Len returns the SetRollPitchYawSpeedThrust Message Length 3731 func (*SetRollPitchYawSpeedThrust) Len() uint8 { 3732 return 18 3733 } 3734 3735 // Crc returns the SetRollPitchYawSpeedThrust Message CRC 3736 func (*SetRollPitchYawSpeedThrust) Crc() uint8 { 3737 return 24 3738 } 3739 3740 // Pack returns a packed byte array which represents a SetRollPitchYawSpeedThrust payload 3741 func (m *SetRollPitchYawSpeedThrust) Pack() []byte { 3742 data := new(bytes.Buffer) 3743 binary.Write(data, binary.LittleEndian, m.ROLL_SPEED) 3744 binary.Write(data, binary.LittleEndian, m.PITCH_SPEED) 3745 binary.Write(data, binary.LittleEndian, m.YAW_SPEED) 3746 binary.Write(data, binary.LittleEndian, m.THRUST) 3747 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 3748 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 3749 return data.Bytes() 3750 } 3751 3752 // Decode accepts a packed byte array and populates the fields of the SetRollPitchYawSpeedThrust 3753 func (m *SetRollPitchYawSpeedThrust) Decode(buf []byte) { 3754 data := bytes.NewBuffer(buf) 3755 binary.Read(data, binary.LittleEndian, &m.ROLL_SPEED) 3756 binary.Read(data, binary.LittleEndian, &m.PITCH_SPEED) 3757 binary.Read(data, binary.LittleEndian, &m.YAW_SPEED) 3758 binary.Read(data, binary.LittleEndian, &m.THRUST) 3759 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 3760 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 3761 } 3762 3763 // 3764 // MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT 3765 // 3766 // MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT 58 3767 // 3768 // MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN 20 3769 // 3770 // MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC 239 3771 // 3772 // 3773 type RollPitchYawThrustSetpoint struct { 3774 TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot 3775 ROLL float32 // Desired roll angle in radians 3776 PITCH float32 // Desired pitch angle in radians 3777 YAW float32 // Desired yaw angle in radians 3778 THRUST float32 // Collective thrust, normalized to 0 .. 1 3779 } 3780 3781 // NewRollPitchYawThrustSetpoint returns a new RollPitchYawThrustSetpoint 3782 func NewRollPitchYawThrustSetpoint(TIME_BOOT_MS uint32, ROLL float32, PITCH float32, YAW float32, THRUST float32) *RollPitchYawThrustSetpoint { 3783 m := RollPitchYawThrustSetpoint{} 3784 m.TIME_BOOT_MS = TIME_BOOT_MS 3785 m.ROLL = ROLL 3786 m.PITCH = PITCH 3787 m.YAW = YAW 3788 m.THRUST = THRUST 3789 return &m 3790 } 3791 3792 // Id returns the RollPitchYawThrustSetpoint Message ID 3793 func (*RollPitchYawThrustSetpoint) Id() uint8 { 3794 return 58 3795 } 3796 3797 // Len returns the RollPitchYawThrustSetpoint Message Length 3798 func (*RollPitchYawThrustSetpoint) Len() uint8 { 3799 return 20 3800 } 3801 3802 // Crc returns the RollPitchYawThrustSetpoint Message CRC 3803 func (*RollPitchYawThrustSetpoint) Crc() uint8 { 3804 return 239 3805 } 3806 3807 // Pack returns a packed byte array which represents a RollPitchYawThrustSetpoint payload 3808 func (m *RollPitchYawThrustSetpoint) Pack() []byte { 3809 data := new(bytes.Buffer) 3810 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 3811 binary.Write(data, binary.LittleEndian, m.ROLL) 3812 binary.Write(data, binary.LittleEndian, m.PITCH) 3813 binary.Write(data, binary.LittleEndian, m.YAW) 3814 binary.Write(data, binary.LittleEndian, m.THRUST) 3815 return data.Bytes() 3816 } 3817 3818 // Decode accepts a packed byte array and populates the fields of the RollPitchYawThrustSetpoint 3819 func (m *RollPitchYawThrustSetpoint) Decode(buf []byte) { 3820 data := bytes.NewBuffer(buf) 3821 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 3822 binary.Read(data, binary.LittleEndian, &m.ROLL) 3823 binary.Read(data, binary.LittleEndian, &m.PITCH) 3824 binary.Read(data, binary.LittleEndian, &m.YAW) 3825 binary.Read(data, binary.LittleEndian, &m.THRUST) 3826 } 3827 3828 // 3829 // MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 3830 // 3831 // MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 59 3832 // 3833 // MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN 20 3834 // 3835 // MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC 238 3836 // 3837 // 3838 type RollPitchYawSpeedThrustSetpoint struct { 3839 TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot 3840 ROLL_SPEED float32 // Desired roll angular speed in rad/s 3841 PITCH_SPEED float32 // Desired pitch angular speed in rad/s 3842 YAW_SPEED float32 // Desired yaw angular speed in rad/s 3843 THRUST float32 // Collective thrust, normalized to 0 .. 1 3844 } 3845 3846 // NewRollPitchYawSpeedThrustSetpoint returns a new RollPitchYawSpeedThrustSetpoint 3847 func NewRollPitchYawSpeedThrustSetpoint(TIME_BOOT_MS uint32, ROLL_SPEED float32, PITCH_SPEED float32, YAW_SPEED float32, THRUST float32) *RollPitchYawSpeedThrustSetpoint { 3848 m := RollPitchYawSpeedThrustSetpoint{} 3849 m.TIME_BOOT_MS = TIME_BOOT_MS 3850 m.ROLL_SPEED = ROLL_SPEED 3851 m.PITCH_SPEED = PITCH_SPEED 3852 m.YAW_SPEED = YAW_SPEED 3853 m.THRUST = THRUST 3854 return &m 3855 } 3856 3857 // Id returns the RollPitchYawSpeedThrustSetpoint Message ID 3858 func (*RollPitchYawSpeedThrustSetpoint) Id() uint8 { 3859 return 59 3860 } 3861 3862 // Len returns the RollPitchYawSpeedThrustSetpoint Message Length 3863 func (*RollPitchYawSpeedThrustSetpoint) Len() uint8 { 3864 return 20 3865 } 3866 3867 // Crc returns the RollPitchYawSpeedThrustSetpoint Message CRC 3868 func (*RollPitchYawSpeedThrustSetpoint) Crc() uint8 { 3869 return 238 3870 } 3871 3872 // Pack returns a packed byte array which represents a RollPitchYawSpeedThrustSetpoint payload 3873 func (m *RollPitchYawSpeedThrustSetpoint) Pack() []byte { 3874 data := new(bytes.Buffer) 3875 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 3876 binary.Write(data, binary.LittleEndian, m.ROLL_SPEED) 3877 binary.Write(data, binary.LittleEndian, m.PITCH_SPEED) 3878 binary.Write(data, binary.LittleEndian, m.YAW_SPEED) 3879 binary.Write(data, binary.LittleEndian, m.THRUST) 3880 return data.Bytes() 3881 } 3882 3883 // Decode accepts a packed byte array and populates the fields of the RollPitchYawSpeedThrustSetpoint 3884 func (m *RollPitchYawSpeedThrustSetpoint) Decode(buf []byte) { 3885 data := bytes.NewBuffer(buf) 3886 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 3887 binary.Read(data, binary.LittleEndian, &m.ROLL_SPEED) 3888 binary.Read(data, binary.LittleEndian, &m.PITCH_SPEED) 3889 binary.Read(data, binary.LittleEndian, &m.YAW_SPEED) 3890 binary.Read(data, binary.LittleEndian, &m.THRUST) 3891 } 3892 3893 // 3894 // MESSAGE SET_QUAD_MOTORS_SETPOINT 3895 // 3896 // MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT 60 3897 // 3898 // MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN 9 3899 // 3900 // MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC 30 3901 // 3902 // 3903 type SetQuadMotorsSetpoint struct { 3904 MOTOR_FRONT_NW uint16 // Front motor in + configuration, front left motor in x configuration 3905 MOTOR_RIGHT_NE uint16 // Right motor in + configuration, front right motor in x configuration 3906 MOTOR_BACK_SE uint16 // Back motor in + configuration, back right motor in x configuration 3907 MOTOR_LEFT_SW uint16 // Left motor in + configuration, back left motor in x configuration 3908 TARGET_SYSTEM uint8 // System ID of the system that should set these motor commands 3909 } 3910 3911 // NewSetQuadMotorsSetpoint returns a new SetQuadMotorsSetpoint 3912 func NewSetQuadMotorsSetpoint(MOTOR_FRONT_NW uint16, MOTOR_RIGHT_NE uint16, MOTOR_BACK_SE uint16, MOTOR_LEFT_SW uint16, TARGET_SYSTEM uint8) *SetQuadMotorsSetpoint { 3913 m := SetQuadMotorsSetpoint{} 3914 m.MOTOR_FRONT_NW = MOTOR_FRONT_NW 3915 m.MOTOR_RIGHT_NE = MOTOR_RIGHT_NE 3916 m.MOTOR_BACK_SE = MOTOR_BACK_SE 3917 m.MOTOR_LEFT_SW = MOTOR_LEFT_SW 3918 m.TARGET_SYSTEM = TARGET_SYSTEM 3919 return &m 3920 } 3921 3922 // Id returns the SetQuadMotorsSetpoint Message ID 3923 func (*SetQuadMotorsSetpoint) Id() uint8 { 3924 return 60 3925 } 3926 3927 // Len returns the SetQuadMotorsSetpoint Message Length 3928 func (*SetQuadMotorsSetpoint) Len() uint8 { 3929 return 9 3930 } 3931 3932 // Crc returns the SetQuadMotorsSetpoint Message CRC 3933 func (*SetQuadMotorsSetpoint) Crc() uint8 { 3934 return 30 3935 } 3936 3937 // Pack returns a packed byte array which represents a SetQuadMotorsSetpoint payload 3938 func (m *SetQuadMotorsSetpoint) Pack() []byte { 3939 data := new(bytes.Buffer) 3940 binary.Write(data, binary.LittleEndian, m.MOTOR_FRONT_NW) 3941 binary.Write(data, binary.LittleEndian, m.MOTOR_RIGHT_NE) 3942 binary.Write(data, binary.LittleEndian, m.MOTOR_BACK_SE) 3943 binary.Write(data, binary.LittleEndian, m.MOTOR_LEFT_SW) 3944 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 3945 return data.Bytes() 3946 } 3947 3948 // Decode accepts a packed byte array and populates the fields of the SetQuadMotorsSetpoint 3949 func (m *SetQuadMotorsSetpoint) Decode(buf []byte) { 3950 data := bytes.NewBuffer(buf) 3951 binary.Read(data, binary.LittleEndian, &m.MOTOR_FRONT_NW) 3952 binary.Read(data, binary.LittleEndian, &m.MOTOR_RIGHT_NE) 3953 binary.Read(data, binary.LittleEndian, &m.MOTOR_BACK_SE) 3954 binary.Read(data, binary.LittleEndian, &m.MOTOR_LEFT_SW) 3955 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 3956 } 3957 3958 // 3959 // MESSAGE SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST 3960 // 3961 // MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST 61 3962 // 3963 // MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN 34 3964 // 3965 // MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC 240 3966 // 3967 // 3968 type SetQuadSwarmRollPitchYawThrust struct { 3969 ROLL [4]int16 // Desired roll angle in radians +-PI (+-INT16_MAX) 3970 PITCH [4]int16 // Desired pitch angle in radians +-PI (+-INT16_MAX) 3971 YAW [4]int16 // Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) 3972 THRUST [4]uint16 // Collective thrust, scaled to uint16 (0..UINT16_MAX) 3973 GROUP uint8 // ID of the quadrotor group (0 - 255, up to 256 groups supported) 3974 MODE uint8 // ID of the flight mode (0 - 255, up to 256 modes supported) 3975 } 3976 3977 // NewSetQuadSwarmRollPitchYawThrust returns a new SetQuadSwarmRollPitchYawThrust 3978 func NewSetQuadSwarmRollPitchYawThrust(ROLL [4]int16, PITCH [4]int16, YAW [4]int16, THRUST [4]uint16, GROUP uint8, MODE uint8) *SetQuadSwarmRollPitchYawThrust { 3979 m := SetQuadSwarmRollPitchYawThrust{} 3980 m.ROLL = ROLL 3981 m.PITCH = PITCH 3982 m.YAW = YAW 3983 m.THRUST = THRUST 3984 m.GROUP = GROUP 3985 m.MODE = MODE 3986 return &m 3987 } 3988 3989 // Id returns the SetQuadSwarmRollPitchYawThrust Message ID 3990 func (*SetQuadSwarmRollPitchYawThrust) Id() uint8 { 3991 return 61 3992 } 3993 3994 // Len returns the SetQuadSwarmRollPitchYawThrust Message Length 3995 func (*SetQuadSwarmRollPitchYawThrust) Len() uint8 { 3996 return 34 3997 } 3998 3999 // Crc returns the SetQuadSwarmRollPitchYawThrust Message CRC 4000 func (*SetQuadSwarmRollPitchYawThrust) Crc() uint8 { 4001 return 240 4002 } 4003 4004 // Pack returns a packed byte array which represents a SetQuadSwarmRollPitchYawThrust payload 4005 func (m *SetQuadSwarmRollPitchYawThrust) Pack() []byte { 4006 data := new(bytes.Buffer) 4007 binary.Write(data, binary.LittleEndian, m.ROLL) 4008 binary.Write(data, binary.LittleEndian, m.PITCH) 4009 binary.Write(data, binary.LittleEndian, m.YAW) 4010 binary.Write(data, binary.LittleEndian, m.THRUST) 4011 binary.Write(data, binary.LittleEndian, m.GROUP) 4012 binary.Write(data, binary.LittleEndian, m.MODE) 4013 return data.Bytes() 4014 } 4015 4016 // Decode accepts a packed byte array and populates the fields of the SetQuadSwarmRollPitchYawThrust 4017 func (m *SetQuadSwarmRollPitchYawThrust) Decode(buf []byte) { 4018 data := bytes.NewBuffer(buf) 4019 binary.Read(data, binary.LittleEndian, &m.ROLL) 4020 binary.Read(data, binary.LittleEndian, &m.PITCH) 4021 binary.Read(data, binary.LittleEndian, &m.YAW) 4022 binary.Read(data, binary.LittleEndian, &m.THRUST) 4023 binary.Read(data, binary.LittleEndian, &m.GROUP) 4024 binary.Read(data, binary.LittleEndian, &m.MODE) 4025 } 4026 4027 const ( 4028 MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_roll_LEN = 4 4029 MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_pitch_LEN = 4 4030 MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_yaw_LEN = 4 4031 MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_thrust_LEN = 4 4032 ) 4033 4034 // 4035 // MESSAGE NAV_CONTROLLER_OUTPUT 4036 // 4037 // MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 4038 // 4039 // MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 4040 // 4041 // MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183 4042 // 4043 // 4044 type NavControllerOutput struct { 4045 NAV_ROLL float32 // Current desired roll in degrees 4046 NAV_PITCH float32 // Current desired pitch in degrees 4047 ALT_ERROR float32 // Current altitude error in meters 4048 ASPD_ERROR float32 // Current airspeed error in meters/second 4049 XTRACK_ERROR float32 // Current crosstrack error on x-y plane in meters 4050 NAV_BEARING int16 // Current desired heading in degrees 4051 TARGET_BEARING int16 // Bearing to current MISSION/target in degrees 4052 WP_DIST uint16 // Distance to active MISSION in meters 4053 } 4054 4055 // NewNavControllerOutput returns a new NavControllerOutput 4056 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 { 4057 m := NavControllerOutput{} 4058 m.NAV_ROLL = NAV_ROLL 4059 m.NAV_PITCH = NAV_PITCH 4060 m.ALT_ERROR = ALT_ERROR 4061 m.ASPD_ERROR = ASPD_ERROR 4062 m.XTRACK_ERROR = XTRACK_ERROR 4063 m.NAV_BEARING = NAV_BEARING 4064 m.TARGET_BEARING = TARGET_BEARING 4065 m.WP_DIST = WP_DIST 4066 return &m 4067 } 4068 4069 // Id returns the NavControllerOutput Message ID 4070 func (*NavControllerOutput) Id() uint8 { 4071 return 62 4072 } 4073 4074 // Len returns the NavControllerOutput Message Length 4075 func (*NavControllerOutput) Len() uint8 { 4076 return 26 4077 } 4078 4079 // Crc returns the NavControllerOutput Message CRC 4080 func (*NavControllerOutput) Crc() uint8 { 4081 return 183 4082 } 4083 4084 // Pack returns a packed byte array which represents a NavControllerOutput payload 4085 func (m *NavControllerOutput) Pack() []byte { 4086 data := new(bytes.Buffer) 4087 binary.Write(data, binary.LittleEndian, m.NAV_ROLL) 4088 binary.Write(data, binary.LittleEndian, m.NAV_PITCH) 4089 binary.Write(data, binary.LittleEndian, m.ALT_ERROR) 4090 binary.Write(data, binary.LittleEndian, m.ASPD_ERROR) 4091 binary.Write(data, binary.LittleEndian, m.XTRACK_ERROR) 4092 binary.Write(data, binary.LittleEndian, m.NAV_BEARING) 4093 binary.Write(data, binary.LittleEndian, m.TARGET_BEARING) 4094 binary.Write(data, binary.LittleEndian, m.WP_DIST) 4095 return data.Bytes() 4096 } 4097 4098 // Decode accepts a packed byte array and populates the fields of the NavControllerOutput 4099 func (m *NavControllerOutput) Decode(buf []byte) { 4100 data := bytes.NewBuffer(buf) 4101 binary.Read(data, binary.LittleEndian, &m.NAV_ROLL) 4102 binary.Read(data, binary.LittleEndian, &m.NAV_PITCH) 4103 binary.Read(data, binary.LittleEndian, &m.ALT_ERROR) 4104 binary.Read(data, binary.LittleEndian, &m.ASPD_ERROR) 4105 binary.Read(data, binary.LittleEndian, &m.XTRACK_ERROR) 4106 binary.Read(data, binary.LittleEndian, &m.NAV_BEARING) 4107 binary.Read(data, binary.LittleEndian, &m.TARGET_BEARING) 4108 binary.Read(data, binary.LittleEndian, &m.WP_DIST) 4109 } 4110 4111 // 4112 // MESSAGE SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST 4113 // 4114 // MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST 63 4115 // 4116 // MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN 46 4117 // 4118 // MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC 130 4119 // 4120 // 4121 type SetQuadSwarmLedRollPitchYawThrust struct { 4122 ROLL [4]int16 // Desired roll angle in radians +-PI (+-INT16_MAX) 4123 PITCH [4]int16 // Desired pitch angle in radians +-PI (+-INT16_MAX) 4124 YAW [4]int16 // Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) 4125 THRUST [4]uint16 // Collective thrust, scaled to uint16 (0..UINT16_MAX) 4126 GROUP uint8 // ID of the quadrotor group (0 - 255, up to 256 groups supported) 4127 MODE uint8 // ID of the flight mode (0 - 255, up to 256 modes supported) 4128 LED_RED [4]uint8 // RGB red channel (0-255) 4129 LED_BLUE [4]uint8 // RGB green channel (0-255) 4130 LED_GREEN [4]uint8 // RGB blue channel (0-255) 4131 } 4132 4133 // NewSetQuadSwarmLedRollPitchYawThrust returns a new SetQuadSwarmLedRollPitchYawThrust 4134 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 { 4135 m := SetQuadSwarmLedRollPitchYawThrust{} 4136 m.ROLL = ROLL 4137 m.PITCH = PITCH 4138 m.YAW = YAW 4139 m.THRUST = THRUST 4140 m.GROUP = GROUP 4141 m.MODE = MODE 4142 m.LED_RED = LED_RED 4143 m.LED_BLUE = LED_BLUE 4144 m.LED_GREEN = LED_GREEN 4145 return &m 4146 } 4147 4148 // Id returns the SetQuadSwarmLedRollPitchYawThrust Message ID 4149 func (*SetQuadSwarmLedRollPitchYawThrust) Id() uint8 { 4150 return 63 4151 } 4152 4153 // Len returns the SetQuadSwarmLedRollPitchYawThrust Message Length 4154 func (*SetQuadSwarmLedRollPitchYawThrust) Len() uint8 { 4155 return 46 4156 } 4157 4158 // Crc returns the SetQuadSwarmLedRollPitchYawThrust Message CRC 4159 func (*SetQuadSwarmLedRollPitchYawThrust) Crc() uint8 { 4160 return 130 4161 } 4162 4163 // Pack returns a packed byte array which represents a SetQuadSwarmLedRollPitchYawThrust payload 4164 func (m *SetQuadSwarmLedRollPitchYawThrust) Pack() []byte { 4165 data := new(bytes.Buffer) 4166 binary.Write(data, binary.LittleEndian, m.ROLL) 4167 binary.Write(data, binary.LittleEndian, m.PITCH) 4168 binary.Write(data, binary.LittleEndian, m.YAW) 4169 binary.Write(data, binary.LittleEndian, m.THRUST) 4170 binary.Write(data, binary.LittleEndian, m.GROUP) 4171 binary.Write(data, binary.LittleEndian, m.MODE) 4172 binary.Write(data, binary.LittleEndian, m.LED_RED) 4173 binary.Write(data, binary.LittleEndian, m.LED_BLUE) 4174 binary.Write(data, binary.LittleEndian, m.LED_GREEN) 4175 return data.Bytes() 4176 } 4177 4178 // Decode accepts a packed byte array and populates the fields of the SetQuadSwarmLedRollPitchYawThrust 4179 func (m *SetQuadSwarmLedRollPitchYawThrust) Decode(buf []byte) { 4180 data := bytes.NewBuffer(buf) 4181 binary.Read(data, binary.LittleEndian, &m.ROLL) 4182 binary.Read(data, binary.LittleEndian, &m.PITCH) 4183 binary.Read(data, binary.LittleEndian, &m.YAW) 4184 binary.Read(data, binary.LittleEndian, &m.THRUST) 4185 binary.Read(data, binary.LittleEndian, &m.GROUP) 4186 binary.Read(data, binary.LittleEndian, &m.MODE) 4187 binary.Read(data, binary.LittleEndian, &m.LED_RED) 4188 binary.Read(data, binary.LittleEndian, &m.LED_BLUE) 4189 binary.Read(data, binary.LittleEndian, &m.LED_GREEN) 4190 } 4191 4192 const ( 4193 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_roll_LEN = 4 4194 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_pitch_LEN = 4 4195 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_yaw_LEN = 4 4196 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_thrust_LEN = 4 4197 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_led_red_LEN = 4 4198 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_led_blue_LEN = 4 4199 MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_led_green_LEN = 4 4200 ) 4201 4202 // 4203 // MESSAGE STATE_CORRECTION 4204 // 4205 // MAVLINK_MSG_ID_STATE_CORRECTION 64 4206 // 4207 // MAVLINK_MSG_ID_STATE_CORRECTION_LEN 36 4208 // 4209 // MAVLINK_MSG_ID_STATE_CORRECTION_CRC 130 4210 // 4211 // 4212 type StateCorrection struct { 4213 XERR float32 // x position error 4214 YERR float32 // y position error 4215 ZERR float32 // z position error 4216 ROLLERR float32 // roll error (radians) 4217 PITCHERR float32 // pitch error (radians) 4218 YAWERR float32 // yaw error (radians) 4219 VXERR float32 // x velocity 4220 VYERR float32 // y velocity 4221 VZERR float32 // z velocity 4222 } 4223 4224 // NewStateCorrection returns a new StateCorrection 4225 func NewStateCorrection(XERR float32, YERR float32, ZERR float32, ROLLERR float32, PITCHERR float32, YAWERR float32, VXERR float32, VYERR float32, VZERR float32) *StateCorrection { 4226 m := StateCorrection{} 4227 m.XERR = XERR 4228 m.YERR = YERR 4229 m.ZERR = ZERR 4230 m.ROLLERR = ROLLERR 4231 m.PITCHERR = PITCHERR 4232 m.YAWERR = YAWERR 4233 m.VXERR = VXERR 4234 m.VYERR = VYERR 4235 m.VZERR = VZERR 4236 return &m 4237 } 4238 4239 // Id returns the StateCorrection Message ID 4240 func (*StateCorrection) Id() uint8 { 4241 return 64 4242 } 4243 4244 // Len returns the StateCorrection Message Length 4245 func (*StateCorrection) Len() uint8 { 4246 return 36 4247 } 4248 4249 // Crc returns the StateCorrection Message CRC 4250 func (*StateCorrection) Crc() uint8 { 4251 return 130 4252 } 4253 4254 // Pack returns a packed byte array which represents a StateCorrection payload 4255 func (m *StateCorrection) Pack() []byte { 4256 data := new(bytes.Buffer) 4257 binary.Write(data, binary.LittleEndian, m.XERR) 4258 binary.Write(data, binary.LittleEndian, m.YERR) 4259 binary.Write(data, binary.LittleEndian, m.ZERR) 4260 binary.Write(data, binary.LittleEndian, m.ROLLERR) 4261 binary.Write(data, binary.LittleEndian, m.PITCHERR) 4262 binary.Write(data, binary.LittleEndian, m.YAWERR) 4263 binary.Write(data, binary.LittleEndian, m.VXERR) 4264 binary.Write(data, binary.LittleEndian, m.VYERR) 4265 binary.Write(data, binary.LittleEndian, m.VZERR) 4266 return data.Bytes() 4267 } 4268 4269 // Decode accepts a packed byte array and populates the fields of the StateCorrection 4270 func (m *StateCorrection) Decode(buf []byte) { 4271 data := bytes.NewBuffer(buf) 4272 binary.Read(data, binary.LittleEndian, &m.XERR) 4273 binary.Read(data, binary.LittleEndian, &m.YERR) 4274 binary.Read(data, binary.LittleEndian, &m.ZERR) 4275 binary.Read(data, binary.LittleEndian, &m.ROLLERR) 4276 binary.Read(data, binary.LittleEndian, &m.PITCHERR) 4277 binary.Read(data, binary.LittleEndian, &m.YAWERR) 4278 binary.Read(data, binary.LittleEndian, &m.VXERR) 4279 binary.Read(data, binary.LittleEndian, &m.VYERR) 4280 binary.Read(data, binary.LittleEndian, &m.VZERR) 4281 } 4282 4283 // 4284 // MESSAGE RC_CHANNELS 4285 // 4286 // MAVLINK_MSG_ID_RC_CHANNELS 65 4287 // 4288 // MAVLINK_MSG_ID_RC_CHANNELS_LEN 42 4289 // 4290 // MAVLINK_MSG_ID_RC_CHANNELS_CRC 118 4291 // 4292 // 4293 type RcChannels struct { 4294 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 4295 CHAN1_RAW uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4296 CHAN2_RAW uint16 // RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4297 CHAN3_RAW uint16 // RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4298 CHAN4_RAW uint16 // RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4299 CHAN5_RAW uint16 // RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4300 CHAN6_RAW uint16 // RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4301 CHAN7_RAW uint16 // RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4302 CHAN8_RAW uint16 // RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4303 CHAN9_RAW uint16 // RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4304 CHAN10_RAW uint16 // RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4305 CHAN11_RAW uint16 // RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4306 CHAN12_RAW uint16 // RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4307 CHAN13_RAW uint16 // RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4308 CHAN14_RAW uint16 // RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4309 CHAN15_RAW uint16 // RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4310 CHAN16_RAW uint16 // RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4311 CHAN17_RAW uint16 // RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4312 CHAN18_RAW uint16 // RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. 4313 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. 4314 RSSI uint8 // Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. 4315 } 4316 4317 // NewRcChannels returns a new RcChannels 4318 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 { 4319 m := RcChannels{} 4320 m.TIME_BOOT_MS = TIME_BOOT_MS 4321 m.CHAN1_RAW = CHAN1_RAW 4322 m.CHAN2_RAW = CHAN2_RAW 4323 m.CHAN3_RAW = CHAN3_RAW 4324 m.CHAN4_RAW = CHAN4_RAW 4325 m.CHAN5_RAW = CHAN5_RAW 4326 m.CHAN6_RAW = CHAN6_RAW 4327 m.CHAN7_RAW = CHAN7_RAW 4328 m.CHAN8_RAW = CHAN8_RAW 4329 m.CHAN9_RAW = CHAN9_RAW 4330 m.CHAN10_RAW = CHAN10_RAW 4331 m.CHAN11_RAW = CHAN11_RAW 4332 m.CHAN12_RAW = CHAN12_RAW 4333 m.CHAN13_RAW = CHAN13_RAW 4334 m.CHAN14_RAW = CHAN14_RAW 4335 m.CHAN15_RAW = CHAN15_RAW 4336 m.CHAN16_RAW = CHAN16_RAW 4337 m.CHAN17_RAW = CHAN17_RAW 4338 m.CHAN18_RAW = CHAN18_RAW 4339 m.CHANCOUNT = CHANCOUNT 4340 m.RSSI = RSSI 4341 return &m 4342 } 4343 4344 // Id returns the RcChannels Message ID 4345 func (*RcChannels) Id() uint8 { 4346 return 65 4347 } 4348 4349 // Len returns the RcChannels Message Length 4350 func (*RcChannels) Len() uint8 { 4351 return 42 4352 } 4353 4354 // Crc returns the RcChannels Message CRC 4355 func (*RcChannels) Crc() uint8 { 4356 return 118 4357 } 4358 4359 // Pack returns a packed byte array which represents a RcChannels payload 4360 func (m *RcChannels) Pack() []byte { 4361 data := new(bytes.Buffer) 4362 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 4363 binary.Write(data, binary.LittleEndian, m.CHAN1_RAW) 4364 binary.Write(data, binary.LittleEndian, m.CHAN2_RAW) 4365 binary.Write(data, binary.LittleEndian, m.CHAN3_RAW) 4366 binary.Write(data, binary.LittleEndian, m.CHAN4_RAW) 4367 binary.Write(data, binary.LittleEndian, m.CHAN5_RAW) 4368 binary.Write(data, binary.LittleEndian, m.CHAN6_RAW) 4369 binary.Write(data, binary.LittleEndian, m.CHAN7_RAW) 4370 binary.Write(data, binary.LittleEndian, m.CHAN8_RAW) 4371 binary.Write(data, binary.LittleEndian, m.CHAN9_RAW) 4372 binary.Write(data, binary.LittleEndian, m.CHAN10_RAW) 4373 binary.Write(data, binary.LittleEndian, m.CHAN11_RAW) 4374 binary.Write(data, binary.LittleEndian, m.CHAN12_RAW) 4375 binary.Write(data, binary.LittleEndian, m.CHAN13_RAW) 4376 binary.Write(data, binary.LittleEndian, m.CHAN14_RAW) 4377 binary.Write(data, binary.LittleEndian, m.CHAN15_RAW) 4378 binary.Write(data, binary.LittleEndian, m.CHAN16_RAW) 4379 binary.Write(data, binary.LittleEndian, m.CHAN17_RAW) 4380 binary.Write(data, binary.LittleEndian, m.CHAN18_RAW) 4381 binary.Write(data, binary.LittleEndian, m.CHANCOUNT) 4382 binary.Write(data, binary.LittleEndian, m.RSSI) 4383 return data.Bytes() 4384 } 4385 4386 // Decode accepts a packed byte array and populates the fields of the RcChannels 4387 func (m *RcChannels) Decode(buf []byte) { 4388 data := bytes.NewBuffer(buf) 4389 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 4390 binary.Read(data, binary.LittleEndian, &m.CHAN1_RAW) 4391 binary.Read(data, binary.LittleEndian, &m.CHAN2_RAW) 4392 binary.Read(data, binary.LittleEndian, &m.CHAN3_RAW) 4393 binary.Read(data, binary.LittleEndian, &m.CHAN4_RAW) 4394 binary.Read(data, binary.LittleEndian, &m.CHAN5_RAW) 4395 binary.Read(data, binary.LittleEndian, &m.CHAN6_RAW) 4396 binary.Read(data, binary.LittleEndian, &m.CHAN7_RAW) 4397 binary.Read(data, binary.LittleEndian, &m.CHAN8_RAW) 4398 binary.Read(data, binary.LittleEndian, &m.CHAN9_RAW) 4399 binary.Read(data, binary.LittleEndian, &m.CHAN10_RAW) 4400 binary.Read(data, binary.LittleEndian, &m.CHAN11_RAW) 4401 binary.Read(data, binary.LittleEndian, &m.CHAN12_RAW) 4402 binary.Read(data, binary.LittleEndian, &m.CHAN13_RAW) 4403 binary.Read(data, binary.LittleEndian, &m.CHAN14_RAW) 4404 binary.Read(data, binary.LittleEndian, &m.CHAN15_RAW) 4405 binary.Read(data, binary.LittleEndian, &m.CHAN16_RAW) 4406 binary.Read(data, binary.LittleEndian, &m.CHAN17_RAW) 4407 binary.Read(data, binary.LittleEndian, &m.CHAN18_RAW) 4408 binary.Read(data, binary.LittleEndian, &m.CHANCOUNT) 4409 binary.Read(data, binary.LittleEndian, &m.RSSI) 4410 } 4411 4412 // 4413 // MESSAGE REQUEST_DATA_STREAM 4414 // 4415 // MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 4416 // 4417 // MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 4418 // 4419 // MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148 4420 // 4421 // 4422 type RequestDataStream struct { 4423 REQ_MESSAGE_RATE uint16 // The requested interval between two messages of this type 4424 TARGET_SYSTEM uint8 // The target requested to send the message stream. 4425 TARGET_COMPONENT uint8 // The target requested to send the message stream. 4426 REQ_STREAM_ID uint8 // The ID of the requested data stream 4427 START_STOP uint8 // 1 to start sending, 0 to stop sending. 4428 } 4429 4430 // NewRequestDataStream returns a new RequestDataStream 4431 func NewRequestDataStream(REQ_MESSAGE_RATE uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, REQ_STREAM_ID uint8, START_STOP uint8) *RequestDataStream { 4432 m := RequestDataStream{} 4433 m.REQ_MESSAGE_RATE = REQ_MESSAGE_RATE 4434 m.TARGET_SYSTEM = TARGET_SYSTEM 4435 m.TARGET_COMPONENT = TARGET_COMPONENT 4436 m.REQ_STREAM_ID = REQ_STREAM_ID 4437 m.START_STOP = START_STOP 4438 return &m 4439 } 4440 4441 // Id returns the RequestDataStream Message ID 4442 func (*RequestDataStream) Id() uint8 { 4443 return 66 4444 } 4445 4446 // Len returns the RequestDataStream Message Length 4447 func (*RequestDataStream) Len() uint8 { 4448 return 6 4449 } 4450 4451 // Crc returns the RequestDataStream Message CRC 4452 func (*RequestDataStream) Crc() uint8 { 4453 return 148 4454 } 4455 4456 // Pack returns a packed byte array which represents a RequestDataStream payload 4457 func (m *RequestDataStream) Pack() []byte { 4458 data := new(bytes.Buffer) 4459 binary.Write(data, binary.LittleEndian, m.REQ_MESSAGE_RATE) 4460 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 4461 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 4462 binary.Write(data, binary.LittleEndian, m.REQ_STREAM_ID) 4463 binary.Write(data, binary.LittleEndian, m.START_STOP) 4464 return data.Bytes() 4465 } 4466 4467 // Decode accepts a packed byte array and populates the fields of the RequestDataStream 4468 func (m *RequestDataStream) Decode(buf []byte) { 4469 data := bytes.NewBuffer(buf) 4470 binary.Read(data, binary.LittleEndian, &m.REQ_MESSAGE_RATE) 4471 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 4472 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 4473 binary.Read(data, binary.LittleEndian, &m.REQ_STREAM_ID) 4474 binary.Read(data, binary.LittleEndian, &m.START_STOP) 4475 } 4476 4477 // 4478 // MESSAGE DATA_STREAM 4479 // 4480 // MAVLINK_MSG_ID_DATA_STREAM 67 4481 // 4482 // MAVLINK_MSG_ID_DATA_STREAM_LEN 4 4483 // 4484 // MAVLINK_MSG_ID_DATA_STREAM_CRC 21 4485 // 4486 // 4487 type DataStream struct { 4488 MESSAGE_RATE uint16 // The requested interval between two messages of this type 4489 STREAM_ID uint8 // The ID of the requested data stream 4490 ON_OFF uint8 // 1 stream is enabled, 0 stream is stopped. 4491 } 4492 4493 // NewDataStream returns a new DataStream 4494 func NewDataStream(MESSAGE_RATE uint16, STREAM_ID uint8, ON_OFF uint8) *DataStream { 4495 m := DataStream{} 4496 m.MESSAGE_RATE = MESSAGE_RATE 4497 m.STREAM_ID = STREAM_ID 4498 m.ON_OFF = ON_OFF 4499 return &m 4500 } 4501 4502 // Id returns the DataStream Message ID 4503 func (*DataStream) Id() uint8 { 4504 return 67 4505 } 4506 4507 // Len returns the DataStream Message Length 4508 func (*DataStream) Len() uint8 { 4509 return 4 4510 } 4511 4512 // Crc returns the DataStream Message CRC 4513 func (*DataStream) Crc() uint8 { 4514 return 21 4515 } 4516 4517 // Pack returns a packed byte array which represents a DataStream payload 4518 func (m *DataStream) Pack() []byte { 4519 data := new(bytes.Buffer) 4520 binary.Write(data, binary.LittleEndian, m.MESSAGE_RATE) 4521 binary.Write(data, binary.LittleEndian, m.STREAM_ID) 4522 binary.Write(data, binary.LittleEndian, m.ON_OFF) 4523 return data.Bytes() 4524 } 4525 4526 // Decode accepts a packed byte array and populates the fields of the DataStream 4527 func (m *DataStream) Decode(buf []byte) { 4528 data := bytes.NewBuffer(buf) 4529 binary.Read(data, binary.LittleEndian, &m.MESSAGE_RATE) 4530 binary.Read(data, binary.LittleEndian, &m.STREAM_ID) 4531 binary.Read(data, binary.LittleEndian, &m.ON_OFF) 4532 } 4533 4534 // 4535 // MESSAGE MANUAL_CONTROL 4536 // 4537 // MAVLINK_MSG_ID_MANUAL_CONTROL 69 4538 // 4539 // MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11 4540 // 4541 // MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243 4542 // 4543 // 4544 type ManualControl struct { 4545 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. 4546 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. 4547 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. 4548 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. 4549 BUTTONS uint16 // A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. 4550 TARGET uint8 // The system to be controlled. 4551 } 4552 4553 // NewManualControl returns a new ManualControl 4554 func NewManualControl(X int16, Y int16, Z int16, R int16, BUTTONS uint16, TARGET uint8) *ManualControl { 4555 m := ManualControl{} 4556 m.X = X 4557 m.Y = Y 4558 m.Z = Z 4559 m.R = R 4560 m.BUTTONS = BUTTONS 4561 m.TARGET = TARGET 4562 return &m 4563 } 4564 4565 // Id returns the ManualControl Message ID 4566 func (*ManualControl) Id() uint8 { 4567 return 69 4568 } 4569 4570 // Len returns the ManualControl Message Length 4571 func (*ManualControl) Len() uint8 { 4572 return 11 4573 } 4574 4575 // Crc returns the ManualControl Message CRC 4576 func (*ManualControl) Crc() uint8 { 4577 return 243 4578 } 4579 4580 // Pack returns a packed byte array which represents a ManualControl payload 4581 func (m *ManualControl) Pack() []byte { 4582 data := new(bytes.Buffer) 4583 binary.Write(data, binary.LittleEndian, m.X) 4584 binary.Write(data, binary.LittleEndian, m.Y) 4585 binary.Write(data, binary.LittleEndian, m.Z) 4586 binary.Write(data, binary.LittleEndian, m.R) 4587 binary.Write(data, binary.LittleEndian, m.BUTTONS) 4588 binary.Write(data, binary.LittleEndian, m.TARGET) 4589 return data.Bytes() 4590 } 4591 4592 // Decode accepts a packed byte array and populates the fields of the ManualControl 4593 func (m *ManualControl) Decode(buf []byte) { 4594 data := bytes.NewBuffer(buf) 4595 binary.Read(data, binary.LittleEndian, &m.X) 4596 binary.Read(data, binary.LittleEndian, &m.Y) 4597 binary.Read(data, binary.LittleEndian, &m.Z) 4598 binary.Read(data, binary.LittleEndian, &m.R) 4599 binary.Read(data, binary.LittleEndian, &m.BUTTONS) 4600 binary.Read(data, binary.LittleEndian, &m.TARGET) 4601 } 4602 4603 // 4604 // MESSAGE RC_CHANNELS_OVERRIDE 4605 // 4606 // MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 4607 // 4608 // MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 4609 // 4610 // MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124 4611 // 4612 // 4613 type RcChannelsOverride struct { 4614 CHAN1_RAW uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. 4615 CHAN2_RAW uint16 // RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. 4616 CHAN3_RAW uint16 // RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. 4617 CHAN4_RAW uint16 // RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. 4618 CHAN5_RAW uint16 // RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. 4619 CHAN6_RAW uint16 // RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. 4620 CHAN7_RAW uint16 // RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. 4621 CHAN8_RAW uint16 // RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. 4622 TARGET_SYSTEM uint8 // System ID 4623 TARGET_COMPONENT uint8 // Component ID 4624 } 4625 4626 // NewRcChannelsOverride returns a new RcChannelsOverride 4627 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 { 4628 m := RcChannelsOverride{} 4629 m.CHAN1_RAW = CHAN1_RAW 4630 m.CHAN2_RAW = CHAN2_RAW 4631 m.CHAN3_RAW = CHAN3_RAW 4632 m.CHAN4_RAW = CHAN4_RAW 4633 m.CHAN5_RAW = CHAN5_RAW 4634 m.CHAN6_RAW = CHAN6_RAW 4635 m.CHAN7_RAW = CHAN7_RAW 4636 m.CHAN8_RAW = CHAN8_RAW 4637 m.TARGET_SYSTEM = TARGET_SYSTEM 4638 m.TARGET_COMPONENT = TARGET_COMPONENT 4639 return &m 4640 } 4641 4642 // Id returns the RcChannelsOverride Message ID 4643 func (*RcChannelsOverride) Id() uint8 { 4644 return 70 4645 } 4646 4647 // Len returns the RcChannelsOverride Message Length 4648 func (*RcChannelsOverride) Len() uint8 { 4649 return 18 4650 } 4651 4652 // Crc returns the RcChannelsOverride Message CRC 4653 func (*RcChannelsOverride) Crc() uint8 { 4654 return 124 4655 } 4656 4657 // Pack returns a packed byte array which represents a RcChannelsOverride payload 4658 func (m *RcChannelsOverride) Pack() []byte { 4659 data := new(bytes.Buffer) 4660 binary.Write(data, binary.LittleEndian, m.CHAN1_RAW) 4661 binary.Write(data, binary.LittleEndian, m.CHAN2_RAW) 4662 binary.Write(data, binary.LittleEndian, m.CHAN3_RAW) 4663 binary.Write(data, binary.LittleEndian, m.CHAN4_RAW) 4664 binary.Write(data, binary.LittleEndian, m.CHAN5_RAW) 4665 binary.Write(data, binary.LittleEndian, m.CHAN6_RAW) 4666 binary.Write(data, binary.LittleEndian, m.CHAN7_RAW) 4667 binary.Write(data, binary.LittleEndian, m.CHAN8_RAW) 4668 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 4669 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 4670 return data.Bytes() 4671 } 4672 4673 // Decode accepts a packed byte array and populates the fields of the RcChannelsOverride 4674 func (m *RcChannelsOverride) Decode(buf []byte) { 4675 data := bytes.NewBuffer(buf) 4676 binary.Read(data, binary.LittleEndian, &m.CHAN1_RAW) 4677 binary.Read(data, binary.LittleEndian, &m.CHAN2_RAW) 4678 binary.Read(data, binary.LittleEndian, &m.CHAN3_RAW) 4679 binary.Read(data, binary.LittleEndian, &m.CHAN4_RAW) 4680 binary.Read(data, binary.LittleEndian, &m.CHAN5_RAW) 4681 binary.Read(data, binary.LittleEndian, &m.CHAN6_RAW) 4682 binary.Read(data, binary.LittleEndian, &m.CHAN7_RAW) 4683 binary.Read(data, binary.LittleEndian, &m.CHAN8_RAW) 4684 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 4685 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 4686 } 4687 4688 // 4689 // MESSAGE VFR_HUD 4690 // 4691 // MAVLINK_MSG_ID_VFR_HUD 74 4692 // 4693 // MAVLINK_MSG_ID_VFR_HUD_LEN 20 4694 // 4695 // MAVLINK_MSG_ID_VFR_HUD_CRC 20 4696 // 4697 // 4698 type VfrHud struct { 4699 AIRSPEED float32 // Current airspeed in m/s 4700 GROUNDSPEED float32 // Current ground speed in m/s 4701 ALT float32 // Current altitude (MSL), in meters 4702 CLIMB float32 // Current climb rate in meters/second 4703 HEADING int16 // Current heading in degrees, in compass units (0..360, 0=north) 4704 THROTTLE uint16 // Current throttle setting in integer percent, 0 to 100 4705 } 4706 4707 // NewVfrHud returns a new VfrHud 4708 func NewVfrHud(AIRSPEED float32, GROUNDSPEED float32, ALT float32, CLIMB float32, HEADING int16, THROTTLE uint16) *VfrHud { 4709 m := VfrHud{} 4710 m.AIRSPEED = AIRSPEED 4711 m.GROUNDSPEED = GROUNDSPEED 4712 m.ALT = ALT 4713 m.CLIMB = CLIMB 4714 m.HEADING = HEADING 4715 m.THROTTLE = THROTTLE 4716 return &m 4717 } 4718 4719 // Id returns the VfrHud Message ID 4720 func (*VfrHud) Id() uint8 { 4721 return 74 4722 } 4723 4724 // Len returns the VfrHud Message Length 4725 func (*VfrHud) Len() uint8 { 4726 return 20 4727 } 4728 4729 // Crc returns the VfrHud Message CRC 4730 func (*VfrHud) Crc() uint8 { 4731 return 20 4732 } 4733 4734 // Pack returns a packed byte array which represents a VfrHud payload 4735 func (m *VfrHud) Pack() []byte { 4736 data := new(bytes.Buffer) 4737 binary.Write(data, binary.LittleEndian, m.AIRSPEED) 4738 binary.Write(data, binary.LittleEndian, m.GROUNDSPEED) 4739 binary.Write(data, binary.LittleEndian, m.ALT) 4740 binary.Write(data, binary.LittleEndian, m.CLIMB) 4741 binary.Write(data, binary.LittleEndian, m.HEADING) 4742 binary.Write(data, binary.LittleEndian, m.THROTTLE) 4743 return data.Bytes() 4744 } 4745 4746 // Decode accepts a packed byte array and populates the fields of the VfrHud 4747 func (m *VfrHud) Decode(buf []byte) { 4748 data := bytes.NewBuffer(buf) 4749 binary.Read(data, binary.LittleEndian, &m.AIRSPEED) 4750 binary.Read(data, binary.LittleEndian, &m.GROUNDSPEED) 4751 binary.Read(data, binary.LittleEndian, &m.ALT) 4752 binary.Read(data, binary.LittleEndian, &m.CLIMB) 4753 binary.Read(data, binary.LittleEndian, &m.HEADING) 4754 binary.Read(data, binary.LittleEndian, &m.THROTTLE) 4755 } 4756 4757 // 4758 // MESSAGE COMMAND_LONG 4759 // 4760 // MAVLINK_MSG_ID_COMMAND_LONG 76 4761 // 4762 // MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 4763 // 4764 // MAVLINK_MSG_ID_COMMAND_LONG_CRC 152 4765 // 4766 // 4767 type CommandLong struct { 4768 PARAM1 float32 // Parameter 1, as defined by MAV_CMD enum. 4769 PARAM2 float32 // Parameter 2, as defined by MAV_CMD enum. 4770 PARAM3 float32 // Parameter 3, as defined by MAV_CMD enum. 4771 PARAM4 float32 // Parameter 4, as defined by MAV_CMD enum. 4772 PARAM5 float32 // Parameter 5, as defined by MAV_CMD enum. 4773 PARAM6 float32 // Parameter 6, as defined by MAV_CMD enum. 4774 PARAM7 float32 // Parameter 7, as defined by MAV_CMD enum. 4775 COMMAND uint16 // Command ID, as defined by MAV_CMD enum. 4776 TARGET_SYSTEM uint8 // System which should execute the command 4777 TARGET_COMPONENT uint8 // Component which should execute the command, 0 for all components 4778 CONFIRMATION uint8 // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) 4779 } 4780 4781 // NewCommandLong returns a new CommandLong 4782 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 { 4783 m := CommandLong{} 4784 m.PARAM1 = PARAM1 4785 m.PARAM2 = PARAM2 4786 m.PARAM3 = PARAM3 4787 m.PARAM4 = PARAM4 4788 m.PARAM5 = PARAM5 4789 m.PARAM6 = PARAM6 4790 m.PARAM7 = PARAM7 4791 m.COMMAND = COMMAND 4792 m.TARGET_SYSTEM = TARGET_SYSTEM 4793 m.TARGET_COMPONENT = TARGET_COMPONENT 4794 m.CONFIRMATION = CONFIRMATION 4795 return &m 4796 } 4797 4798 // Id returns the CommandLong Message ID 4799 func (*CommandLong) Id() uint8 { 4800 return 76 4801 } 4802 4803 // Len returns the CommandLong Message Length 4804 func (*CommandLong) Len() uint8 { 4805 return 33 4806 } 4807 4808 // Crc returns the CommandLong Message CRC 4809 func (*CommandLong) Crc() uint8 { 4810 return 152 4811 } 4812 4813 // Pack returns a packed byte array which represents a CommandLong payload 4814 func (m *CommandLong) Pack() []byte { 4815 data := new(bytes.Buffer) 4816 binary.Write(data, binary.LittleEndian, m.PARAM1) 4817 binary.Write(data, binary.LittleEndian, m.PARAM2) 4818 binary.Write(data, binary.LittleEndian, m.PARAM3) 4819 binary.Write(data, binary.LittleEndian, m.PARAM4) 4820 binary.Write(data, binary.LittleEndian, m.PARAM5) 4821 binary.Write(data, binary.LittleEndian, m.PARAM6) 4822 binary.Write(data, binary.LittleEndian, m.PARAM7) 4823 binary.Write(data, binary.LittleEndian, m.COMMAND) 4824 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 4825 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 4826 binary.Write(data, binary.LittleEndian, m.CONFIRMATION) 4827 return data.Bytes() 4828 } 4829 4830 // Decode accepts a packed byte array and populates the fields of the CommandLong 4831 func (m *CommandLong) Decode(buf []byte) { 4832 data := bytes.NewBuffer(buf) 4833 binary.Read(data, binary.LittleEndian, &m.PARAM1) 4834 binary.Read(data, binary.LittleEndian, &m.PARAM2) 4835 binary.Read(data, binary.LittleEndian, &m.PARAM3) 4836 binary.Read(data, binary.LittleEndian, &m.PARAM4) 4837 binary.Read(data, binary.LittleEndian, &m.PARAM5) 4838 binary.Read(data, binary.LittleEndian, &m.PARAM6) 4839 binary.Read(data, binary.LittleEndian, &m.PARAM7) 4840 binary.Read(data, binary.LittleEndian, &m.COMMAND) 4841 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 4842 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 4843 binary.Read(data, binary.LittleEndian, &m.CONFIRMATION) 4844 } 4845 4846 // 4847 // MESSAGE COMMAND_ACK 4848 // 4849 // MAVLINK_MSG_ID_COMMAND_ACK 77 4850 // 4851 // MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 4852 // 4853 // MAVLINK_MSG_ID_COMMAND_ACK_CRC 143 4854 // 4855 // 4856 type CommandAck struct { 4857 COMMAND uint16 // Command ID, as defined by MAV_CMD enum. 4858 RESULT uint8 // See MAV_RESULT enum 4859 } 4860 4861 // NewCommandAck returns a new CommandAck 4862 func NewCommandAck(COMMAND uint16, RESULT uint8) *CommandAck { 4863 m := CommandAck{} 4864 m.COMMAND = COMMAND 4865 m.RESULT = RESULT 4866 return &m 4867 } 4868 4869 // Id returns the CommandAck Message ID 4870 func (*CommandAck) Id() uint8 { 4871 return 77 4872 } 4873 4874 // Len returns the CommandAck Message Length 4875 func (*CommandAck) Len() uint8 { 4876 return 3 4877 } 4878 4879 // Crc returns the CommandAck Message CRC 4880 func (*CommandAck) Crc() uint8 { 4881 return 143 4882 } 4883 4884 // Pack returns a packed byte array which represents a CommandAck payload 4885 func (m *CommandAck) Pack() []byte { 4886 data := new(bytes.Buffer) 4887 binary.Write(data, binary.LittleEndian, m.COMMAND) 4888 binary.Write(data, binary.LittleEndian, m.RESULT) 4889 return data.Bytes() 4890 } 4891 4892 // Decode accepts a packed byte array and populates the fields of the CommandAck 4893 func (m *CommandAck) Decode(buf []byte) { 4894 data := bytes.NewBuffer(buf) 4895 binary.Read(data, binary.LittleEndian, &m.COMMAND) 4896 binary.Read(data, binary.LittleEndian, &m.RESULT) 4897 } 4898 4899 // 4900 // MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT 4901 // 4902 // MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT 80 4903 // 4904 // MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN 20 4905 // 4906 // MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC 127 4907 // 4908 // 4909 type RollPitchYawRatesThrustSetpoint struct { 4910 TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot 4911 ROLL_RATE float32 // Desired roll rate in radians per second 4912 PITCH_RATE float32 // Desired pitch rate in radians per second 4913 YAW_RATE float32 // Desired yaw rate in radians per second 4914 THRUST float32 // Collective thrust, normalized to 0 .. 1 4915 } 4916 4917 // NewRollPitchYawRatesThrustSetpoint returns a new RollPitchYawRatesThrustSetpoint 4918 func NewRollPitchYawRatesThrustSetpoint(TIME_BOOT_MS uint32, ROLL_RATE float32, PITCH_RATE float32, YAW_RATE float32, THRUST float32) *RollPitchYawRatesThrustSetpoint { 4919 m := RollPitchYawRatesThrustSetpoint{} 4920 m.TIME_BOOT_MS = TIME_BOOT_MS 4921 m.ROLL_RATE = ROLL_RATE 4922 m.PITCH_RATE = PITCH_RATE 4923 m.YAW_RATE = YAW_RATE 4924 m.THRUST = THRUST 4925 return &m 4926 } 4927 4928 // Id returns the RollPitchYawRatesThrustSetpoint Message ID 4929 func (*RollPitchYawRatesThrustSetpoint) Id() uint8 { 4930 return 80 4931 } 4932 4933 // Len returns the RollPitchYawRatesThrustSetpoint Message Length 4934 func (*RollPitchYawRatesThrustSetpoint) Len() uint8 { 4935 return 20 4936 } 4937 4938 // Crc returns the RollPitchYawRatesThrustSetpoint Message CRC 4939 func (*RollPitchYawRatesThrustSetpoint) Crc() uint8 { 4940 return 127 4941 } 4942 4943 // Pack returns a packed byte array which represents a RollPitchYawRatesThrustSetpoint payload 4944 func (m *RollPitchYawRatesThrustSetpoint) Pack() []byte { 4945 data := new(bytes.Buffer) 4946 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 4947 binary.Write(data, binary.LittleEndian, m.ROLL_RATE) 4948 binary.Write(data, binary.LittleEndian, m.PITCH_RATE) 4949 binary.Write(data, binary.LittleEndian, m.YAW_RATE) 4950 binary.Write(data, binary.LittleEndian, m.THRUST) 4951 return data.Bytes() 4952 } 4953 4954 // Decode accepts a packed byte array and populates the fields of the RollPitchYawRatesThrustSetpoint 4955 func (m *RollPitchYawRatesThrustSetpoint) Decode(buf []byte) { 4956 data := bytes.NewBuffer(buf) 4957 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 4958 binary.Read(data, binary.LittleEndian, &m.ROLL_RATE) 4959 binary.Read(data, binary.LittleEndian, &m.PITCH_RATE) 4960 binary.Read(data, binary.LittleEndian, &m.YAW_RATE) 4961 binary.Read(data, binary.LittleEndian, &m.THRUST) 4962 } 4963 4964 // 4965 // MESSAGE MANUAL_SETPOINT 4966 // 4967 // MAVLINK_MSG_ID_MANUAL_SETPOINT 81 4968 // 4969 // MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22 4970 // 4971 // MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC 106 4972 // 4973 // 4974 type ManualSetpoint struct { 4975 TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot 4976 ROLL float32 // Desired roll rate in radians per second 4977 PITCH float32 // Desired pitch rate in radians per second 4978 YAW float32 // Desired yaw rate in radians per second 4979 THRUST float32 // Collective thrust, normalized to 0 .. 1 4980 MODE_SWITCH uint8 // Flight mode switch position, 0.. 255 4981 MANUAL_OVERRIDE_SWITCH uint8 // Override mode switch position, 0.. 255 4982 } 4983 4984 // NewManualSetpoint returns a new ManualSetpoint 4985 func NewManualSetpoint(TIME_BOOT_MS uint32, ROLL float32, PITCH float32, YAW float32, THRUST float32, MODE_SWITCH uint8, MANUAL_OVERRIDE_SWITCH uint8) *ManualSetpoint { 4986 m := ManualSetpoint{} 4987 m.TIME_BOOT_MS = TIME_BOOT_MS 4988 m.ROLL = ROLL 4989 m.PITCH = PITCH 4990 m.YAW = YAW 4991 m.THRUST = THRUST 4992 m.MODE_SWITCH = MODE_SWITCH 4993 m.MANUAL_OVERRIDE_SWITCH = MANUAL_OVERRIDE_SWITCH 4994 return &m 4995 } 4996 4997 // Id returns the ManualSetpoint Message ID 4998 func (*ManualSetpoint) Id() uint8 { 4999 return 81 5000 } 5001 5002 // Len returns the ManualSetpoint Message Length 5003 func (*ManualSetpoint) Len() uint8 { 5004 return 22 5005 } 5006 5007 // Crc returns the ManualSetpoint Message CRC 5008 func (*ManualSetpoint) Crc() uint8 { 5009 return 106 5010 } 5011 5012 // Pack returns a packed byte array which represents a ManualSetpoint payload 5013 func (m *ManualSetpoint) Pack() []byte { 5014 data := new(bytes.Buffer) 5015 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 5016 binary.Write(data, binary.LittleEndian, m.ROLL) 5017 binary.Write(data, binary.LittleEndian, m.PITCH) 5018 binary.Write(data, binary.LittleEndian, m.YAW) 5019 binary.Write(data, binary.LittleEndian, m.THRUST) 5020 binary.Write(data, binary.LittleEndian, m.MODE_SWITCH) 5021 binary.Write(data, binary.LittleEndian, m.MANUAL_OVERRIDE_SWITCH) 5022 return data.Bytes() 5023 } 5024 5025 // Decode accepts a packed byte array and populates the fields of the ManualSetpoint 5026 func (m *ManualSetpoint) Decode(buf []byte) { 5027 data := bytes.NewBuffer(buf) 5028 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 5029 binary.Read(data, binary.LittleEndian, &m.ROLL) 5030 binary.Read(data, binary.LittleEndian, &m.PITCH) 5031 binary.Read(data, binary.LittleEndian, &m.YAW) 5032 binary.Read(data, binary.LittleEndian, &m.THRUST) 5033 binary.Read(data, binary.LittleEndian, &m.MODE_SWITCH) 5034 binary.Read(data, binary.LittleEndian, &m.MANUAL_OVERRIDE_SWITCH) 5035 } 5036 5037 // 5038 // MESSAGE ATTITUDE_SETPOINT_EXTERNAL 5039 // 5040 // MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL 82 5041 // 5042 // MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN 39 5043 // 5044 // MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_CRC 147 5045 // 5046 // 5047 type AttitudeSetpointExternal struct { 5048 TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot 5049 Q [4]float32 // Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) 5050 BODY_ROLL_RATE float32 // Body roll rate in radians per second 5051 BODY_PITCH_RATE float32 // Body roll rate in radians per second 5052 BODY_YAW_RATE float32 // Body roll rate in radians per second 5053 THRUST float32 // Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) 5054 TARGET_SYSTEM uint8 // System ID 5055 TARGET_COMPONENT uint8 // Component ID 5056 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 5057 } 5058 5059 // NewAttitudeSetpointExternal returns a new AttitudeSetpointExternal 5060 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 { 5061 m := AttitudeSetpointExternal{} 5062 m.TIME_BOOT_MS = TIME_BOOT_MS 5063 m.Q = Q 5064 m.BODY_ROLL_RATE = BODY_ROLL_RATE 5065 m.BODY_PITCH_RATE = BODY_PITCH_RATE 5066 m.BODY_YAW_RATE = BODY_YAW_RATE 5067 m.THRUST = THRUST 5068 m.TARGET_SYSTEM = TARGET_SYSTEM 5069 m.TARGET_COMPONENT = TARGET_COMPONENT 5070 m.TYPE_MASK = TYPE_MASK 5071 return &m 5072 } 5073 5074 // Id returns the AttitudeSetpointExternal Message ID 5075 func (*AttitudeSetpointExternal) Id() uint8 { 5076 return 82 5077 } 5078 5079 // Len returns the AttitudeSetpointExternal Message Length 5080 func (*AttitudeSetpointExternal) Len() uint8 { 5081 return 39 5082 } 5083 5084 // Crc returns the AttitudeSetpointExternal Message CRC 5085 func (*AttitudeSetpointExternal) Crc() uint8 { 5086 return 147 5087 } 5088 5089 // Pack returns a packed byte array which represents a AttitudeSetpointExternal payload 5090 func (m *AttitudeSetpointExternal) Pack() []byte { 5091 data := new(bytes.Buffer) 5092 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 5093 binary.Write(data, binary.LittleEndian, m.Q) 5094 binary.Write(data, binary.LittleEndian, m.BODY_ROLL_RATE) 5095 binary.Write(data, binary.LittleEndian, m.BODY_PITCH_RATE) 5096 binary.Write(data, binary.LittleEndian, m.BODY_YAW_RATE) 5097 binary.Write(data, binary.LittleEndian, m.THRUST) 5098 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 5099 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 5100 binary.Write(data, binary.LittleEndian, m.TYPE_MASK) 5101 return data.Bytes() 5102 } 5103 5104 // Decode accepts a packed byte array and populates the fields of the AttitudeSetpointExternal 5105 func (m *AttitudeSetpointExternal) Decode(buf []byte) { 5106 data := bytes.NewBuffer(buf) 5107 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 5108 binary.Read(data, binary.LittleEndian, &m.Q) 5109 binary.Read(data, binary.LittleEndian, &m.BODY_ROLL_RATE) 5110 binary.Read(data, binary.LittleEndian, &m.BODY_PITCH_RATE) 5111 binary.Read(data, binary.LittleEndian, &m.BODY_YAW_RATE) 5112 binary.Read(data, binary.LittleEndian, &m.THRUST) 5113 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 5114 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 5115 binary.Read(data, binary.LittleEndian, &m.TYPE_MASK) 5116 } 5117 5118 const ( 5119 MAVLINK_MSG_ATTITUDE_SETPOINT_EXTERNAL_FIELD_q_LEN = 4 5120 ) 5121 5122 // 5123 // MESSAGE LOCAL_NED_POSITION_SETPOINT_EXTERNAL 5124 // 5125 // MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL 83 5126 // 5127 // MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN 45 5128 // 5129 // MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC 211 5130 // 5131 // 5132 type LocalNedPositionSetpointExternal struct { 5133 TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot 5134 X float32 // X Position in NED frame in meters 5135 Y float32 // Y Position in NED frame in meters 5136 Z float32 // Z Position in NED frame in meters (note, altitude is negative in NED) 5137 VX float32 // X velocity in NED frame in meter / s 5138 VY float32 // Y velocity in NED frame in meter / s 5139 VZ float32 // Z velocity in NED frame in meter / s 5140 AFX float32 // X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N 5141 AFY float32 // Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N 5142 AFZ float32 // Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N 5143 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 5144 TARGET_SYSTEM uint8 // System ID 5145 TARGET_COMPONENT uint8 // Component ID 5146 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 5147 } 5148 5149 // NewLocalNedPositionSetpointExternal returns a new LocalNedPositionSetpointExternal 5150 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 { 5151 m := LocalNedPositionSetpointExternal{} 5152 m.TIME_BOOT_MS = TIME_BOOT_MS 5153 m.X = X 5154 m.Y = Y 5155 m.Z = Z 5156 m.VX = VX 5157 m.VY = VY 5158 m.VZ = VZ 5159 m.AFX = AFX 5160 m.AFY = AFY 5161 m.AFZ = AFZ 5162 m.TYPE_MASK = TYPE_MASK 5163 m.TARGET_SYSTEM = TARGET_SYSTEM 5164 m.TARGET_COMPONENT = TARGET_COMPONENT 5165 m.COORDINATE_FRAME = COORDINATE_FRAME 5166 return &m 5167 } 5168 5169 // Id returns the LocalNedPositionSetpointExternal Message ID 5170 func (*LocalNedPositionSetpointExternal) Id() uint8 { 5171 return 83 5172 } 5173 5174 // Len returns the LocalNedPositionSetpointExternal Message Length 5175 func (*LocalNedPositionSetpointExternal) Len() uint8 { 5176 return 45 5177 } 5178 5179 // Crc returns the LocalNedPositionSetpointExternal Message CRC 5180 func (*LocalNedPositionSetpointExternal) Crc() uint8 { 5181 return 211 5182 } 5183 5184 // Pack returns a packed byte array which represents a LocalNedPositionSetpointExternal payload 5185 func (m *LocalNedPositionSetpointExternal) Pack() []byte { 5186 data := new(bytes.Buffer) 5187 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 5188 binary.Write(data, binary.LittleEndian, m.X) 5189 binary.Write(data, binary.LittleEndian, m.Y) 5190 binary.Write(data, binary.LittleEndian, m.Z) 5191 binary.Write(data, binary.LittleEndian, m.VX) 5192 binary.Write(data, binary.LittleEndian, m.VY) 5193 binary.Write(data, binary.LittleEndian, m.VZ) 5194 binary.Write(data, binary.LittleEndian, m.AFX) 5195 binary.Write(data, binary.LittleEndian, m.AFY) 5196 binary.Write(data, binary.LittleEndian, m.AFZ) 5197 binary.Write(data, binary.LittleEndian, m.TYPE_MASK) 5198 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 5199 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 5200 binary.Write(data, binary.LittleEndian, m.COORDINATE_FRAME) 5201 return data.Bytes() 5202 } 5203 5204 // Decode accepts a packed byte array and populates the fields of the LocalNedPositionSetpointExternal 5205 func (m *LocalNedPositionSetpointExternal) Decode(buf []byte) { 5206 data := bytes.NewBuffer(buf) 5207 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 5208 binary.Read(data, binary.LittleEndian, &m.X) 5209 binary.Read(data, binary.LittleEndian, &m.Y) 5210 binary.Read(data, binary.LittleEndian, &m.Z) 5211 binary.Read(data, binary.LittleEndian, &m.VX) 5212 binary.Read(data, binary.LittleEndian, &m.VY) 5213 binary.Read(data, binary.LittleEndian, &m.VZ) 5214 binary.Read(data, binary.LittleEndian, &m.AFX) 5215 binary.Read(data, binary.LittleEndian, &m.AFY) 5216 binary.Read(data, binary.LittleEndian, &m.AFZ) 5217 binary.Read(data, binary.LittleEndian, &m.TYPE_MASK) 5218 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 5219 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 5220 binary.Read(data, binary.LittleEndian, &m.COORDINATE_FRAME) 5221 } 5222 5223 // 5224 // MESSAGE GLOBAL_POSITION_SETPOINT_EXTERNAL_INT 5225 // 5226 // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT 84 5227 // 5228 // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN 44 5229 // 5230 // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC 198 5231 // 5232 // 5233 type GlobalPositionSetpointExternalInt struct { 5234 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. 5235 LAT_INT int32 // X Position in WGS84 frame in 1e7 * meters 5236 LON_INT int32 // Y Position in WGS84 frame in 1e7 * meters 5237 ALT float32 // Altitude in WGS84, not AMSL 5238 VX float32 // X velocity in NED frame in meter / s 5239 VY float32 // Y velocity in NED frame in meter / s 5240 VZ float32 // Z velocity in NED frame in meter / s 5241 AFX float32 // X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N 5242 AFY float32 // Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N 5243 AFZ float32 // Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N 5244 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 5245 TARGET_SYSTEM uint8 // System ID 5246 TARGET_COMPONENT uint8 // Component ID 5247 } 5248 5249 // NewGlobalPositionSetpointExternalInt returns a new GlobalPositionSetpointExternalInt 5250 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 { 5251 m := GlobalPositionSetpointExternalInt{} 5252 m.TIME_BOOT_MS = TIME_BOOT_MS 5253 m.LAT_INT = LAT_INT 5254 m.LON_INT = LON_INT 5255 m.ALT = ALT 5256 m.VX = VX 5257 m.VY = VY 5258 m.VZ = VZ 5259 m.AFX = AFX 5260 m.AFY = AFY 5261 m.AFZ = AFZ 5262 m.TYPE_MASK = TYPE_MASK 5263 m.TARGET_SYSTEM = TARGET_SYSTEM 5264 m.TARGET_COMPONENT = TARGET_COMPONENT 5265 return &m 5266 } 5267 5268 // Id returns the GlobalPositionSetpointExternalInt Message ID 5269 func (*GlobalPositionSetpointExternalInt) Id() uint8 { 5270 return 84 5271 } 5272 5273 // Len returns the GlobalPositionSetpointExternalInt Message Length 5274 func (*GlobalPositionSetpointExternalInt) Len() uint8 { 5275 return 44 5276 } 5277 5278 // Crc returns the GlobalPositionSetpointExternalInt Message CRC 5279 func (*GlobalPositionSetpointExternalInt) Crc() uint8 { 5280 return 198 5281 } 5282 5283 // Pack returns a packed byte array which represents a GlobalPositionSetpointExternalInt payload 5284 func (m *GlobalPositionSetpointExternalInt) Pack() []byte { 5285 data := new(bytes.Buffer) 5286 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 5287 binary.Write(data, binary.LittleEndian, m.LAT_INT) 5288 binary.Write(data, binary.LittleEndian, m.LON_INT) 5289 binary.Write(data, binary.LittleEndian, m.ALT) 5290 binary.Write(data, binary.LittleEndian, m.VX) 5291 binary.Write(data, binary.LittleEndian, m.VY) 5292 binary.Write(data, binary.LittleEndian, m.VZ) 5293 binary.Write(data, binary.LittleEndian, m.AFX) 5294 binary.Write(data, binary.LittleEndian, m.AFY) 5295 binary.Write(data, binary.LittleEndian, m.AFZ) 5296 binary.Write(data, binary.LittleEndian, m.TYPE_MASK) 5297 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 5298 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 5299 return data.Bytes() 5300 } 5301 5302 // Decode accepts a packed byte array and populates the fields of the GlobalPositionSetpointExternalInt 5303 func (m *GlobalPositionSetpointExternalInt) Decode(buf []byte) { 5304 data := bytes.NewBuffer(buf) 5305 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 5306 binary.Read(data, binary.LittleEndian, &m.LAT_INT) 5307 binary.Read(data, binary.LittleEndian, &m.LON_INT) 5308 binary.Read(data, binary.LittleEndian, &m.ALT) 5309 binary.Read(data, binary.LittleEndian, &m.VX) 5310 binary.Read(data, binary.LittleEndian, &m.VY) 5311 binary.Read(data, binary.LittleEndian, &m.VZ) 5312 binary.Read(data, binary.LittleEndian, &m.AFX) 5313 binary.Read(data, binary.LittleEndian, &m.AFY) 5314 binary.Read(data, binary.LittleEndian, &m.AFZ) 5315 binary.Read(data, binary.LittleEndian, &m.TYPE_MASK) 5316 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 5317 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 5318 } 5319 5320 // 5321 // MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 5322 // 5323 // MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89 5324 // 5325 // MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28 5326 // 5327 // MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231 5328 // 5329 // 5330 type LocalPositionNedSystemGlobalOffset struct { 5331 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 5332 X float32 // X Position 5333 Y float32 // Y Position 5334 Z float32 // Z Position 5335 ROLL float32 // Roll 5336 PITCH float32 // Pitch 5337 YAW float32 // Yaw 5338 } 5339 5340 // NewLocalPositionNedSystemGlobalOffset returns a new LocalPositionNedSystemGlobalOffset 5341 func NewLocalPositionNedSystemGlobalOffset(TIME_BOOT_MS uint32, X float32, Y float32, Z float32, ROLL float32, PITCH float32, YAW float32) *LocalPositionNedSystemGlobalOffset { 5342 m := LocalPositionNedSystemGlobalOffset{} 5343 m.TIME_BOOT_MS = TIME_BOOT_MS 5344 m.X = X 5345 m.Y = Y 5346 m.Z = Z 5347 m.ROLL = ROLL 5348 m.PITCH = PITCH 5349 m.YAW = YAW 5350 return &m 5351 } 5352 5353 // Id returns the LocalPositionNedSystemGlobalOffset Message ID 5354 func (*LocalPositionNedSystemGlobalOffset) Id() uint8 { 5355 return 89 5356 } 5357 5358 // Len returns the LocalPositionNedSystemGlobalOffset Message Length 5359 func (*LocalPositionNedSystemGlobalOffset) Len() uint8 { 5360 return 28 5361 } 5362 5363 // Crc returns the LocalPositionNedSystemGlobalOffset Message CRC 5364 func (*LocalPositionNedSystemGlobalOffset) Crc() uint8 { 5365 return 231 5366 } 5367 5368 // Pack returns a packed byte array which represents a LocalPositionNedSystemGlobalOffset payload 5369 func (m *LocalPositionNedSystemGlobalOffset) Pack() []byte { 5370 data := new(bytes.Buffer) 5371 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 5372 binary.Write(data, binary.LittleEndian, m.X) 5373 binary.Write(data, binary.LittleEndian, m.Y) 5374 binary.Write(data, binary.LittleEndian, m.Z) 5375 binary.Write(data, binary.LittleEndian, m.ROLL) 5376 binary.Write(data, binary.LittleEndian, m.PITCH) 5377 binary.Write(data, binary.LittleEndian, m.YAW) 5378 return data.Bytes() 5379 } 5380 5381 // Decode accepts a packed byte array and populates the fields of the LocalPositionNedSystemGlobalOffset 5382 func (m *LocalPositionNedSystemGlobalOffset) Decode(buf []byte) { 5383 data := bytes.NewBuffer(buf) 5384 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 5385 binary.Read(data, binary.LittleEndian, &m.X) 5386 binary.Read(data, binary.LittleEndian, &m.Y) 5387 binary.Read(data, binary.LittleEndian, &m.Z) 5388 binary.Read(data, binary.LittleEndian, &m.ROLL) 5389 binary.Read(data, binary.LittleEndian, &m.PITCH) 5390 binary.Read(data, binary.LittleEndian, &m.YAW) 5391 } 5392 5393 // 5394 // MESSAGE HIL_STATE 5395 // 5396 // MAVLINK_MSG_ID_HIL_STATE 90 5397 // 5398 // MAVLINK_MSG_ID_HIL_STATE_LEN 56 5399 // 5400 // MAVLINK_MSG_ID_HIL_STATE_CRC 183 5401 // 5402 // 5403 type HilState struct { 5404 TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) 5405 ROLL float32 // Roll angle (rad) 5406 PITCH float32 // Pitch angle (rad) 5407 YAW float32 // Yaw angle (rad) 5408 ROLLSPEED float32 // Body frame roll / phi angular speed (rad/s) 5409 PITCHSPEED float32 // Body frame pitch / theta angular speed (rad/s) 5410 YAWSPEED float32 // Body frame yaw / psi angular speed (rad/s) 5411 LAT int32 // Latitude, expressed as * 1E7 5412 LON int32 // Longitude, expressed as * 1E7 5413 ALT int32 // Altitude in meters, expressed as * 1000 (millimeters) 5414 VX int16 // Ground X Speed (Latitude), expressed as m/s * 100 5415 VY int16 // Ground Y Speed (Longitude), expressed as m/s * 100 5416 VZ int16 // Ground Z Speed (Altitude), expressed as m/s * 100 5417 XACC int16 // X acceleration (mg) 5418 YACC int16 // Y acceleration (mg) 5419 ZACC int16 // Z acceleration (mg) 5420 } 5421 5422 // NewHilState returns a new HilState 5423 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 { 5424 m := HilState{} 5425 m.TIME_USEC = TIME_USEC 5426 m.ROLL = ROLL 5427 m.PITCH = PITCH 5428 m.YAW = YAW 5429 m.ROLLSPEED = ROLLSPEED 5430 m.PITCHSPEED = PITCHSPEED 5431 m.YAWSPEED = YAWSPEED 5432 m.LAT = LAT 5433 m.LON = LON 5434 m.ALT = ALT 5435 m.VX = VX 5436 m.VY = VY 5437 m.VZ = VZ 5438 m.XACC = XACC 5439 m.YACC = YACC 5440 m.ZACC = ZACC 5441 return &m 5442 } 5443 5444 // Id returns the HilState Message ID 5445 func (*HilState) Id() uint8 { 5446 return 90 5447 } 5448 5449 // Len returns the HilState Message Length 5450 func (*HilState) Len() uint8 { 5451 return 56 5452 } 5453 5454 // Crc returns the HilState Message CRC 5455 func (*HilState) Crc() uint8 { 5456 return 183 5457 } 5458 5459 // Pack returns a packed byte array which represents a HilState payload 5460 func (m *HilState) Pack() []byte { 5461 data := new(bytes.Buffer) 5462 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 5463 binary.Write(data, binary.LittleEndian, m.ROLL) 5464 binary.Write(data, binary.LittleEndian, m.PITCH) 5465 binary.Write(data, binary.LittleEndian, m.YAW) 5466 binary.Write(data, binary.LittleEndian, m.ROLLSPEED) 5467 binary.Write(data, binary.LittleEndian, m.PITCHSPEED) 5468 binary.Write(data, binary.LittleEndian, m.YAWSPEED) 5469 binary.Write(data, binary.LittleEndian, m.LAT) 5470 binary.Write(data, binary.LittleEndian, m.LON) 5471 binary.Write(data, binary.LittleEndian, m.ALT) 5472 binary.Write(data, binary.LittleEndian, m.VX) 5473 binary.Write(data, binary.LittleEndian, m.VY) 5474 binary.Write(data, binary.LittleEndian, m.VZ) 5475 binary.Write(data, binary.LittleEndian, m.XACC) 5476 binary.Write(data, binary.LittleEndian, m.YACC) 5477 binary.Write(data, binary.LittleEndian, m.ZACC) 5478 return data.Bytes() 5479 } 5480 5481 // Decode accepts a packed byte array and populates the fields of the HilState 5482 func (m *HilState) Decode(buf []byte) { 5483 data := bytes.NewBuffer(buf) 5484 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 5485 binary.Read(data, binary.LittleEndian, &m.ROLL) 5486 binary.Read(data, binary.LittleEndian, &m.PITCH) 5487 binary.Read(data, binary.LittleEndian, &m.YAW) 5488 binary.Read(data, binary.LittleEndian, &m.ROLLSPEED) 5489 binary.Read(data, binary.LittleEndian, &m.PITCHSPEED) 5490 binary.Read(data, binary.LittleEndian, &m.YAWSPEED) 5491 binary.Read(data, binary.LittleEndian, &m.LAT) 5492 binary.Read(data, binary.LittleEndian, &m.LON) 5493 binary.Read(data, binary.LittleEndian, &m.ALT) 5494 binary.Read(data, binary.LittleEndian, &m.VX) 5495 binary.Read(data, binary.LittleEndian, &m.VY) 5496 binary.Read(data, binary.LittleEndian, &m.VZ) 5497 binary.Read(data, binary.LittleEndian, &m.XACC) 5498 binary.Read(data, binary.LittleEndian, &m.YACC) 5499 binary.Read(data, binary.LittleEndian, &m.ZACC) 5500 } 5501 5502 // 5503 // MESSAGE HIL_CONTROLS 5504 // 5505 // MAVLINK_MSG_ID_HIL_CONTROLS 91 5506 // 5507 // MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 5508 // 5509 // MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63 5510 // 5511 // 5512 type HilControls struct { 5513 TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) 5514 ROLL_AILERONS float32 // Control output -1 .. 1 5515 PITCH_ELEVATOR float32 // Control output -1 .. 1 5516 YAW_RUDDER float32 // Control output -1 .. 1 5517 THROTTLE float32 // Throttle 0 .. 1 5518 AUX1 float32 // Aux 1, -1 .. 1 5519 AUX2 float32 // Aux 2, -1 .. 1 5520 AUX3 float32 // Aux 3, -1 .. 1 5521 AUX4 float32 // Aux 4, -1 .. 1 5522 MODE uint8 // System mode (MAV_MODE) 5523 NAV_MODE uint8 // Navigation mode (MAV_NAV_MODE) 5524 } 5525 5526 // NewHilControls returns a new HilControls 5527 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 { 5528 m := HilControls{} 5529 m.TIME_USEC = TIME_USEC 5530 m.ROLL_AILERONS = ROLL_AILERONS 5531 m.PITCH_ELEVATOR = PITCH_ELEVATOR 5532 m.YAW_RUDDER = YAW_RUDDER 5533 m.THROTTLE = THROTTLE 5534 m.AUX1 = AUX1 5535 m.AUX2 = AUX2 5536 m.AUX3 = AUX3 5537 m.AUX4 = AUX4 5538 m.MODE = MODE 5539 m.NAV_MODE = NAV_MODE 5540 return &m 5541 } 5542 5543 // Id returns the HilControls Message ID 5544 func (*HilControls) Id() uint8 { 5545 return 91 5546 } 5547 5548 // Len returns the HilControls Message Length 5549 func (*HilControls) Len() uint8 { 5550 return 42 5551 } 5552 5553 // Crc returns the HilControls Message CRC 5554 func (*HilControls) Crc() uint8 { 5555 return 63 5556 } 5557 5558 // Pack returns a packed byte array which represents a HilControls payload 5559 func (m *HilControls) Pack() []byte { 5560 data := new(bytes.Buffer) 5561 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 5562 binary.Write(data, binary.LittleEndian, m.ROLL_AILERONS) 5563 binary.Write(data, binary.LittleEndian, m.PITCH_ELEVATOR) 5564 binary.Write(data, binary.LittleEndian, m.YAW_RUDDER) 5565 binary.Write(data, binary.LittleEndian, m.THROTTLE) 5566 binary.Write(data, binary.LittleEndian, m.AUX1) 5567 binary.Write(data, binary.LittleEndian, m.AUX2) 5568 binary.Write(data, binary.LittleEndian, m.AUX3) 5569 binary.Write(data, binary.LittleEndian, m.AUX4) 5570 binary.Write(data, binary.LittleEndian, m.MODE) 5571 binary.Write(data, binary.LittleEndian, m.NAV_MODE) 5572 return data.Bytes() 5573 } 5574 5575 // Decode accepts a packed byte array and populates the fields of the HilControls 5576 func (m *HilControls) Decode(buf []byte) { 5577 data := bytes.NewBuffer(buf) 5578 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 5579 binary.Read(data, binary.LittleEndian, &m.ROLL_AILERONS) 5580 binary.Read(data, binary.LittleEndian, &m.PITCH_ELEVATOR) 5581 binary.Read(data, binary.LittleEndian, &m.YAW_RUDDER) 5582 binary.Read(data, binary.LittleEndian, &m.THROTTLE) 5583 binary.Read(data, binary.LittleEndian, &m.AUX1) 5584 binary.Read(data, binary.LittleEndian, &m.AUX2) 5585 binary.Read(data, binary.LittleEndian, &m.AUX3) 5586 binary.Read(data, binary.LittleEndian, &m.AUX4) 5587 binary.Read(data, binary.LittleEndian, &m.MODE) 5588 binary.Read(data, binary.LittleEndian, &m.NAV_MODE) 5589 } 5590 5591 // 5592 // MESSAGE HIL_RC_INPUTS_RAW 5593 // 5594 // MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92 5595 // 5596 // MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 5597 // 5598 // MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC 54 5599 // 5600 // 5601 type HilRcInputsRaw struct { 5602 TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) 5603 CHAN1_RAW uint16 // RC channel 1 value, in microseconds 5604 CHAN2_RAW uint16 // RC channel 2 value, in microseconds 5605 CHAN3_RAW uint16 // RC channel 3 value, in microseconds 5606 CHAN4_RAW uint16 // RC channel 4 value, in microseconds 5607 CHAN5_RAW uint16 // RC channel 5 value, in microseconds 5608 CHAN6_RAW uint16 // RC channel 6 value, in microseconds 5609 CHAN7_RAW uint16 // RC channel 7 value, in microseconds 5610 CHAN8_RAW uint16 // RC channel 8 value, in microseconds 5611 CHAN9_RAW uint16 // RC channel 9 value, in microseconds 5612 CHAN10_RAW uint16 // RC channel 10 value, in microseconds 5613 CHAN11_RAW uint16 // RC channel 11 value, in microseconds 5614 CHAN12_RAW uint16 // RC channel 12 value, in microseconds 5615 RSSI uint8 // Receive signal strength indicator, 0: 0%, 255: 100% 5616 } 5617 5618 // NewHilRcInputsRaw returns a new HilRcInputsRaw 5619 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 { 5620 m := HilRcInputsRaw{} 5621 m.TIME_USEC = TIME_USEC 5622 m.CHAN1_RAW = CHAN1_RAW 5623 m.CHAN2_RAW = CHAN2_RAW 5624 m.CHAN3_RAW = CHAN3_RAW 5625 m.CHAN4_RAW = CHAN4_RAW 5626 m.CHAN5_RAW = CHAN5_RAW 5627 m.CHAN6_RAW = CHAN6_RAW 5628 m.CHAN7_RAW = CHAN7_RAW 5629 m.CHAN8_RAW = CHAN8_RAW 5630 m.CHAN9_RAW = CHAN9_RAW 5631 m.CHAN10_RAW = CHAN10_RAW 5632 m.CHAN11_RAW = CHAN11_RAW 5633 m.CHAN12_RAW = CHAN12_RAW 5634 m.RSSI = RSSI 5635 return &m 5636 } 5637 5638 // Id returns the HilRcInputsRaw Message ID 5639 func (*HilRcInputsRaw) Id() uint8 { 5640 return 92 5641 } 5642 5643 // Len returns the HilRcInputsRaw Message Length 5644 func (*HilRcInputsRaw) Len() uint8 { 5645 return 33 5646 } 5647 5648 // Crc returns the HilRcInputsRaw Message CRC 5649 func (*HilRcInputsRaw) Crc() uint8 { 5650 return 54 5651 } 5652 5653 // Pack returns a packed byte array which represents a HilRcInputsRaw payload 5654 func (m *HilRcInputsRaw) Pack() []byte { 5655 data := new(bytes.Buffer) 5656 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 5657 binary.Write(data, binary.LittleEndian, m.CHAN1_RAW) 5658 binary.Write(data, binary.LittleEndian, m.CHAN2_RAW) 5659 binary.Write(data, binary.LittleEndian, m.CHAN3_RAW) 5660 binary.Write(data, binary.LittleEndian, m.CHAN4_RAW) 5661 binary.Write(data, binary.LittleEndian, m.CHAN5_RAW) 5662 binary.Write(data, binary.LittleEndian, m.CHAN6_RAW) 5663 binary.Write(data, binary.LittleEndian, m.CHAN7_RAW) 5664 binary.Write(data, binary.LittleEndian, m.CHAN8_RAW) 5665 binary.Write(data, binary.LittleEndian, m.CHAN9_RAW) 5666 binary.Write(data, binary.LittleEndian, m.CHAN10_RAW) 5667 binary.Write(data, binary.LittleEndian, m.CHAN11_RAW) 5668 binary.Write(data, binary.LittleEndian, m.CHAN12_RAW) 5669 binary.Write(data, binary.LittleEndian, m.RSSI) 5670 return data.Bytes() 5671 } 5672 5673 // Decode accepts a packed byte array and populates the fields of the HilRcInputsRaw 5674 func (m *HilRcInputsRaw) Decode(buf []byte) { 5675 data := bytes.NewBuffer(buf) 5676 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 5677 binary.Read(data, binary.LittleEndian, &m.CHAN1_RAW) 5678 binary.Read(data, binary.LittleEndian, &m.CHAN2_RAW) 5679 binary.Read(data, binary.LittleEndian, &m.CHAN3_RAW) 5680 binary.Read(data, binary.LittleEndian, &m.CHAN4_RAW) 5681 binary.Read(data, binary.LittleEndian, &m.CHAN5_RAW) 5682 binary.Read(data, binary.LittleEndian, &m.CHAN6_RAW) 5683 binary.Read(data, binary.LittleEndian, &m.CHAN7_RAW) 5684 binary.Read(data, binary.LittleEndian, &m.CHAN8_RAW) 5685 binary.Read(data, binary.LittleEndian, &m.CHAN9_RAW) 5686 binary.Read(data, binary.LittleEndian, &m.CHAN10_RAW) 5687 binary.Read(data, binary.LittleEndian, &m.CHAN11_RAW) 5688 binary.Read(data, binary.LittleEndian, &m.CHAN12_RAW) 5689 binary.Read(data, binary.LittleEndian, &m.RSSI) 5690 } 5691 5692 // 5693 // MESSAGE OPTICAL_FLOW 5694 // 5695 // MAVLINK_MSG_ID_OPTICAL_FLOW 100 5696 // 5697 // MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 5698 // 5699 // MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 5700 // 5701 // 5702 type OpticalFlow struct { 5703 TIME_USEC uint64 // Timestamp (UNIX) 5704 FLOW_COMP_M_X float32 // Flow in meters in x-sensor direction, angular-speed compensated 5705 FLOW_COMP_M_Y float32 // Flow in meters in y-sensor direction, angular-speed compensated 5706 GROUND_DISTANCE float32 // Ground distance in meters. Positive value: distance known. Negative value: Unknown distance 5707 FLOW_X int16 // Flow in pixels * 10 in x-sensor direction (dezi-pixels) 5708 FLOW_Y int16 // Flow in pixels * 10 in y-sensor direction (dezi-pixels) 5709 SENSOR_ID uint8 // Sensor ID 5710 QUALITY uint8 // Optical flow quality / confidence. 0: bad, 255: maximum quality 5711 } 5712 5713 // NewOpticalFlow returns a new OpticalFlow 5714 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 { 5715 m := OpticalFlow{} 5716 m.TIME_USEC = TIME_USEC 5717 m.FLOW_COMP_M_X = FLOW_COMP_M_X 5718 m.FLOW_COMP_M_Y = FLOW_COMP_M_Y 5719 m.GROUND_DISTANCE = GROUND_DISTANCE 5720 m.FLOW_X = FLOW_X 5721 m.FLOW_Y = FLOW_Y 5722 m.SENSOR_ID = SENSOR_ID 5723 m.QUALITY = QUALITY 5724 return &m 5725 } 5726 5727 // Id returns the OpticalFlow Message ID 5728 func (*OpticalFlow) Id() uint8 { 5729 return 100 5730 } 5731 5732 // Len returns the OpticalFlow Message Length 5733 func (*OpticalFlow) Len() uint8 { 5734 return 26 5735 } 5736 5737 // Crc returns the OpticalFlow Message CRC 5738 func (*OpticalFlow) Crc() uint8 { 5739 return 175 5740 } 5741 5742 // Pack returns a packed byte array which represents a OpticalFlow payload 5743 func (m *OpticalFlow) Pack() []byte { 5744 data := new(bytes.Buffer) 5745 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 5746 binary.Write(data, binary.LittleEndian, m.FLOW_COMP_M_X) 5747 binary.Write(data, binary.LittleEndian, m.FLOW_COMP_M_Y) 5748 binary.Write(data, binary.LittleEndian, m.GROUND_DISTANCE) 5749 binary.Write(data, binary.LittleEndian, m.FLOW_X) 5750 binary.Write(data, binary.LittleEndian, m.FLOW_Y) 5751 binary.Write(data, binary.LittleEndian, m.SENSOR_ID) 5752 binary.Write(data, binary.LittleEndian, m.QUALITY) 5753 return data.Bytes() 5754 } 5755 5756 // Decode accepts a packed byte array and populates the fields of the OpticalFlow 5757 func (m *OpticalFlow) Decode(buf []byte) { 5758 data := bytes.NewBuffer(buf) 5759 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 5760 binary.Read(data, binary.LittleEndian, &m.FLOW_COMP_M_X) 5761 binary.Read(data, binary.LittleEndian, &m.FLOW_COMP_M_Y) 5762 binary.Read(data, binary.LittleEndian, &m.GROUND_DISTANCE) 5763 binary.Read(data, binary.LittleEndian, &m.FLOW_X) 5764 binary.Read(data, binary.LittleEndian, &m.FLOW_Y) 5765 binary.Read(data, binary.LittleEndian, &m.SENSOR_ID) 5766 binary.Read(data, binary.LittleEndian, &m.QUALITY) 5767 } 5768 5769 // 5770 // MESSAGE GLOBAL_VISION_POSITION_ESTIMATE 5771 // 5772 // MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101 5773 // 5774 // MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32 5775 // 5776 // MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102 5777 // 5778 // 5779 type GlobalVisionPositionEstimate struct { 5780 USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) 5781 X float32 // Global X position 5782 Y float32 // Global Y position 5783 Z float32 // Global Z position 5784 ROLL float32 // Roll angle in rad 5785 PITCH float32 // Pitch angle in rad 5786 YAW float32 // Yaw angle in rad 5787 } 5788 5789 // NewGlobalVisionPositionEstimate returns a new GlobalVisionPositionEstimate 5790 func NewGlobalVisionPositionEstimate(USEC uint64, X float32, Y float32, Z float32, ROLL float32, PITCH float32, YAW float32) *GlobalVisionPositionEstimate { 5791 m := GlobalVisionPositionEstimate{} 5792 m.USEC = USEC 5793 m.X = X 5794 m.Y = Y 5795 m.Z = Z 5796 m.ROLL = ROLL 5797 m.PITCH = PITCH 5798 m.YAW = YAW 5799 return &m 5800 } 5801 5802 // Id returns the GlobalVisionPositionEstimate Message ID 5803 func (*GlobalVisionPositionEstimate) Id() uint8 { 5804 return 101 5805 } 5806 5807 // Len returns the GlobalVisionPositionEstimate Message Length 5808 func (*GlobalVisionPositionEstimate) Len() uint8 { 5809 return 32 5810 } 5811 5812 // Crc returns the GlobalVisionPositionEstimate Message CRC 5813 func (*GlobalVisionPositionEstimate) Crc() uint8 { 5814 return 102 5815 } 5816 5817 // Pack returns a packed byte array which represents a GlobalVisionPositionEstimate payload 5818 func (m *GlobalVisionPositionEstimate) Pack() []byte { 5819 data := new(bytes.Buffer) 5820 binary.Write(data, binary.LittleEndian, m.USEC) 5821 binary.Write(data, binary.LittleEndian, m.X) 5822 binary.Write(data, binary.LittleEndian, m.Y) 5823 binary.Write(data, binary.LittleEndian, m.Z) 5824 binary.Write(data, binary.LittleEndian, m.ROLL) 5825 binary.Write(data, binary.LittleEndian, m.PITCH) 5826 binary.Write(data, binary.LittleEndian, m.YAW) 5827 return data.Bytes() 5828 } 5829 5830 // Decode accepts a packed byte array and populates the fields of the GlobalVisionPositionEstimate 5831 func (m *GlobalVisionPositionEstimate) Decode(buf []byte) { 5832 data := bytes.NewBuffer(buf) 5833 binary.Read(data, binary.LittleEndian, &m.USEC) 5834 binary.Read(data, binary.LittleEndian, &m.X) 5835 binary.Read(data, binary.LittleEndian, &m.Y) 5836 binary.Read(data, binary.LittleEndian, &m.Z) 5837 binary.Read(data, binary.LittleEndian, &m.ROLL) 5838 binary.Read(data, binary.LittleEndian, &m.PITCH) 5839 binary.Read(data, binary.LittleEndian, &m.YAW) 5840 } 5841 5842 // 5843 // MESSAGE VISION_POSITION_ESTIMATE 5844 // 5845 // MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102 5846 // 5847 // MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 5848 // 5849 // MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC 158 5850 // 5851 // 5852 type VisionPositionEstimate struct { 5853 USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) 5854 X float32 // Global X position 5855 Y float32 // Global Y position 5856 Z float32 // Global Z position 5857 ROLL float32 // Roll angle in rad 5858 PITCH float32 // Pitch angle in rad 5859 YAW float32 // Yaw angle in rad 5860 } 5861 5862 // NewVisionPositionEstimate returns a new VisionPositionEstimate 5863 func NewVisionPositionEstimate(USEC uint64, X float32, Y float32, Z float32, ROLL float32, PITCH float32, YAW float32) *VisionPositionEstimate { 5864 m := VisionPositionEstimate{} 5865 m.USEC = USEC 5866 m.X = X 5867 m.Y = Y 5868 m.Z = Z 5869 m.ROLL = ROLL 5870 m.PITCH = PITCH 5871 m.YAW = YAW 5872 return &m 5873 } 5874 5875 // Id returns the VisionPositionEstimate Message ID 5876 func (*VisionPositionEstimate) Id() uint8 { 5877 return 102 5878 } 5879 5880 // Len returns the VisionPositionEstimate Message Length 5881 func (*VisionPositionEstimate) Len() uint8 { 5882 return 32 5883 } 5884 5885 // Crc returns the VisionPositionEstimate Message CRC 5886 func (*VisionPositionEstimate) Crc() uint8 { 5887 return 158 5888 } 5889 5890 // Pack returns a packed byte array which represents a VisionPositionEstimate payload 5891 func (m *VisionPositionEstimate) Pack() []byte { 5892 data := new(bytes.Buffer) 5893 binary.Write(data, binary.LittleEndian, m.USEC) 5894 binary.Write(data, binary.LittleEndian, m.X) 5895 binary.Write(data, binary.LittleEndian, m.Y) 5896 binary.Write(data, binary.LittleEndian, m.Z) 5897 binary.Write(data, binary.LittleEndian, m.ROLL) 5898 binary.Write(data, binary.LittleEndian, m.PITCH) 5899 binary.Write(data, binary.LittleEndian, m.YAW) 5900 return data.Bytes() 5901 } 5902 5903 // Decode accepts a packed byte array and populates the fields of the VisionPositionEstimate 5904 func (m *VisionPositionEstimate) Decode(buf []byte) { 5905 data := bytes.NewBuffer(buf) 5906 binary.Read(data, binary.LittleEndian, &m.USEC) 5907 binary.Read(data, binary.LittleEndian, &m.X) 5908 binary.Read(data, binary.LittleEndian, &m.Y) 5909 binary.Read(data, binary.LittleEndian, &m.Z) 5910 binary.Read(data, binary.LittleEndian, &m.ROLL) 5911 binary.Read(data, binary.LittleEndian, &m.PITCH) 5912 binary.Read(data, binary.LittleEndian, &m.YAW) 5913 } 5914 5915 // 5916 // MESSAGE VISION_SPEED_ESTIMATE 5917 // 5918 // MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 5919 // 5920 // MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 5921 // 5922 // MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208 5923 // 5924 // 5925 type VisionSpeedEstimate struct { 5926 USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) 5927 X float32 // Global X speed 5928 Y float32 // Global Y speed 5929 Z float32 // Global Z speed 5930 } 5931 5932 // NewVisionSpeedEstimate returns a new VisionSpeedEstimate 5933 func NewVisionSpeedEstimate(USEC uint64, X float32, Y float32, Z float32) *VisionSpeedEstimate { 5934 m := VisionSpeedEstimate{} 5935 m.USEC = USEC 5936 m.X = X 5937 m.Y = Y 5938 m.Z = Z 5939 return &m 5940 } 5941 5942 // Id returns the VisionSpeedEstimate Message ID 5943 func (*VisionSpeedEstimate) Id() uint8 { 5944 return 103 5945 } 5946 5947 // Len returns the VisionSpeedEstimate Message Length 5948 func (*VisionSpeedEstimate) Len() uint8 { 5949 return 20 5950 } 5951 5952 // Crc returns the VisionSpeedEstimate Message CRC 5953 func (*VisionSpeedEstimate) Crc() uint8 { 5954 return 208 5955 } 5956 5957 // Pack returns a packed byte array which represents a VisionSpeedEstimate payload 5958 func (m *VisionSpeedEstimate) Pack() []byte { 5959 data := new(bytes.Buffer) 5960 binary.Write(data, binary.LittleEndian, m.USEC) 5961 binary.Write(data, binary.LittleEndian, m.X) 5962 binary.Write(data, binary.LittleEndian, m.Y) 5963 binary.Write(data, binary.LittleEndian, m.Z) 5964 return data.Bytes() 5965 } 5966 5967 // Decode accepts a packed byte array and populates the fields of the VisionSpeedEstimate 5968 func (m *VisionSpeedEstimate) Decode(buf []byte) { 5969 data := bytes.NewBuffer(buf) 5970 binary.Read(data, binary.LittleEndian, &m.USEC) 5971 binary.Read(data, binary.LittleEndian, &m.X) 5972 binary.Read(data, binary.LittleEndian, &m.Y) 5973 binary.Read(data, binary.LittleEndian, &m.Z) 5974 } 5975 5976 // 5977 // MESSAGE VICON_POSITION_ESTIMATE 5978 // 5979 // MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104 5980 // 5981 // MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 5982 // 5983 // MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC 56 5984 // 5985 // 5986 type ViconPositionEstimate struct { 5987 USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) 5988 X float32 // Global X position 5989 Y float32 // Global Y position 5990 Z float32 // Global Z position 5991 ROLL float32 // Roll angle in rad 5992 PITCH float32 // Pitch angle in rad 5993 YAW float32 // Yaw angle in rad 5994 } 5995 5996 // NewViconPositionEstimate returns a new ViconPositionEstimate 5997 func NewViconPositionEstimate(USEC uint64, X float32, Y float32, Z float32, ROLL float32, PITCH float32, YAW float32) *ViconPositionEstimate { 5998 m := ViconPositionEstimate{} 5999 m.USEC = USEC 6000 m.X = X 6001 m.Y = Y 6002 m.Z = Z 6003 m.ROLL = ROLL 6004 m.PITCH = PITCH 6005 m.YAW = YAW 6006 return &m 6007 } 6008 6009 // Id returns the ViconPositionEstimate Message ID 6010 func (*ViconPositionEstimate) Id() uint8 { 6011 return 104 6012 } 6013 6014 // Len returns the ViconPositionEstimate Message Length 6015 func (*ViconPositionEstimate) Len() uint8 { 6016 return 32 6017 } 6018 6019 // Crc returns the ViconPositionEstimate Message CRC 6020 func (*ViconPositionEstimate) Crc() uint8 { 6021 return 56 6022 } 6023 6024 // Pack returns a packed byte array which represents a ViconPositionEstimate payload 6025 func (m *ViconPositionEstimate) Pack() []byte { 6026 data := new(bytes.Buffer) 6027 binary.Write(data, binary.LittleEndian, m.USEC) 6028 binary.Write(data, binary.LittleEndian, m.X) 6029 binary.Write(data, binary.LittleEndian, m.Y) 6030 binary.Write(data, binary.LittleEndian, m.Z) 6031 binary.Write(data, binary.LittleEndian, m.ROLL) 6032 binary.Write(data, binary.LittleEndian, m.PITCH) 6033 binary.Write(data, binary.LittleEndian, m.YAW) 6034 return data.Bytes() 6035 } 6036 6037 // Decode accepts a packed byte array and populates the fields of the ViconPositionEstimate 6038 func (m *ViconPositionEstimate) Decode(buf []byte) { 6039 data := bytes.NewBuffer(buf) 6040 binary.Read(data, binary.LittleEndian, &m.USEC) 6041 binary.Read(data, binary.LittleEndian, &m.X) 6042 binary.Read(data, binary.LittleEndian, &m.Y) 6043 binary.Read(data, binary.LittleEndian, &m.Z) 6044 binary.Read(data, binary.LittleEndian, &m.ROLL) 6045 binary.Read(data, binary.LittleEndian, &m.PITCH) 6046 binary.Read(data, binary.LittleEndian, &m.YAW) 6047 } 6048 6049 // 6050 // MESSAGE HIGHRES_IMU 6051 // 6052 // MAVLINK_MSG_ID_HIGHRES_IMU 105 6053 // 6054 // MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62 6055 // 6056 // MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93 6057 // 6058 // 6059 type HighresImu struct { 6060 TIME_USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) 6061 XACC float32 // X acceleration (m/s^2) 6062 YACC float32 // Y acceleration (m/s^2) 6063 ZACC float32 // Z acceleration (m/s^2) 6064 XGYRO float32 // Angular speed around X axis (rad / sec) 6065 YGYRO float32 // Angular speed around Y axis (rad / sec) 6066 ZGYRO float32 // Angular speed around Z axis (rad / sec) 6067 XMAG float32 // X Magnetic field (Gauss) 6068 YMAG float32 // Y Magnetic field (Gauss) 6069 ZMAG float32 // Z Magnetic field (Gauss) 6070 ABS_PRESSURE float32 // Absolute pressure in millibar 6071 DIFF_PRESSURE float32 // Differential pressure in millibar 6072 PRESSURE_ALT float32 // Altitude calculated from pressure 6073 TEMPERATURE float32 // Temperature in degrees celsius 6074 FIELDS_UPDATED uint16 // Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature 6075 } 6076 6077 // NewHighresImu returns a new HighresImu 6078 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 { 6079 m := HighresImu{} 6080 m.TIME_USEC = TIME_USEC 6081 m.XACC = XACC 6082 m.YACC = YACC 6083 m.ZACC = ZACC 6084 m.XGYRO = XGYRO 6085 m.YGYRO = YGYRO 6086 m.ZGYRO = ZGYRO 6087 m.XMAG = XMAG 6088 m.YMAG = YMAG 6089 m.ZMAG = ZMAG 6090 m.ABS_PRESSURE = ABS_PRESSURE 6091 m.DIFF_PRESSURE = DIFF_PRESSURE 6092 m.PRESSURE_ALT = PRESSURE_ALT 6093 m.TEMPERATURE = TEMPERATURE 6094 m.FIELDS_UPDATED = FIELDS_UPDATED 6095 return &m 6096 } 6097 6098 // Id returns the HighresImu Message ID 6099 func (*HighresImu) Id() uint8 { 6100 return 105 6101 } 6102 6103 // Len returns the HighresImu Message Length 6104 func (*HighresImu) Len() uint8 { 6105 return 62 6106 } 6107 6108 // Crc returns the HighresImu Message CRC 6109 func (*HighresImu) Crc() uint8 { 6110 return 93 6111 } 6112 6113 // Pack returns a packed byte array which represents a HighresImu payload 6114 func (m *HighresImu) Pack() []byte { 6115 data := new(bytes.Buffer) 6116 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 6117 binary.Write(data, binary.LittleEndian, m.XACC) 6118 binary.Write(data, binary.LittleEndian, m.YACC) 6119 binary.Write(data, binary.LittleEndian, m.ZACC) 6120 binary.Write(data, binary.LittleEndian, m.XGYRO) 6121 binary.Write(data, binary.LittleEndian, m.YGYRO) 6122 binary.Write(data, binary.LittleEndian, m.ZGYRO) 6123 binary.Write(data, binary.LittleEndian, m.XMAG) 6124 binary.Write(data, binary.LittleEndian, m.YMAG) 6125 binary.Write(data, binary.LittleEndian, m.ZMAG) 6126 binary.Write(data, binary.LittleEndian, m.ABS_PRESSURE) 6127 binary.Write(data, binary.LittleEndian, m.DIFF_PRESSURE) 6128 binary.Write(data, binary.LittleEndian, m.PRESSURE_ALT) 6129 binary.Write(data, binary.LittleEndian, m.TEMPERATURE) 6130 binary.Write(data, binary.LittleEndian, m.FIELDS_UPDATED) 6131 return data.Bytes() 6132 } 6133 6134 // Decode accepts a packed byte array and populates the fields of the HighresImu 6135 func (m *HighresImu) Decode(buf []byte) { 6136 data := bytes.NewBuffer(buf) 6137 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 6138 binary.Read(data, binary.LittleEndian, &m.XACC) 6139 binary.Read(data, binary.LittleEndian, &m.YACC) 6140 binary.Read(data, binary.LittleEndian, &m.ZACC) 6141 binary.Read(data, binary.LittleEndian, &m.XGYRO) 6142 binary.Read(data, binary.LittleEndian, &m.YGYRO) 6143 binary.Read(data, binary.LittleEndian, &m.ZGYRO) 6144 binary.Read(data, binary.LittleEndian, &m.XMAG) 6145 binary.Read(data, binary.LittleEndian, &m.YMAG) 6146 binary.Read(data, binary.LittleEndian, &m.ZMAG) 6147 binary.Read(data, binary.LittleEndian, &m.ABS_PRESSURE) 6148 binary.Read(data, binary.LittleEndian, &m.DIFF_PRESSURE) 6149 binary.Read(data, binary.LittleEndian, &m.PRESSURE_ALT) 6150 binary.Read(data, binary.LittleEndian, &m.TEMPERATURE) 6151 binary.Read(data, binary.LittleEndian, &m.FIELDS_UPDATED) 6152 } 6153 6154 // 6155 // MESSAGE OMNIDIRECTIONAL_FLOW 6156 // 6157 // MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW 106 6158 // 6159 // MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN 54 6160 // 6161 // MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC 211 6162 // 6163 // 6164 type OmnidirectionalFlow struct { 6165 TIME_USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) 6166 FRONT_DISTANCE_M float32 // Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance 6167 LEFT [10]int16 // Flow in deci pixels (1 = 0.1 pixel) on left hemisphere 6168 RIGHT [10]int16 // Flow in deci pixels (1 = 0.1 pixel) on right hemisphere 6169 SENSOR_ID uint8 // Sensor ID 6170 QUALITY uint8 // Optical flow quality / confidence. 0: bad, 255: maximum quality 6171 } 6172 6173 // NewOmnidirectionalFlow returns a new OmnidirectionalFlow 6174 func NewOmnidirectionalFlow(TIME_USEC uint64, FRONT_DISTANCE_M float32, LEFT [10]int16, RIGHT [10]int16, SENSOR_ID uint8, QUALITY uint8) *OmnidirectionalFlow { 6175 m := OmnidirectionalFlow{} 6176 m.TIME_USEC = TIME_USEC 6177 m.FRONT_DISTANCE_M = FRONT_DISTANCE_M 6178 m.LEFT = LEFT 6179 m.RIGHT = RIGHT 6180 m.SENSOR_ID = SENSOR_ID 6181 m.QUALITY = QUALITY 6182 return &m 6183 } 6184 6185 // Id returns the OmnidirectionalFlow Message ID 6186 func (*OmnidirectionalFlow) Id() uint8 { 6187 return 106 6188 } 6189 6190 // Len returns the OmnidirectionalFlow Message Length 6191 func (*OmnidirectionalFlow) Len() uint8 { 6192 return 54 6193 } 6194 6195 // Crc returns the OmnidirectionalFlow Message CRC 6196 func (*OmnidirectionalFlow) Crc() uint8 { 6197 return 211 6198 } 6199 6200 // Pack returns a packed byte array which represents a OmnidirectionalFlow payload 6201 func (m *OmnidirectionalFlow) Pack() []byte { 6202 data := new(bytes.Buffer) 6203 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 6204 binary.Write(data, binary.LittleEndian, m.FRONT_DISTANCE_M) 6205 binary.Write(data, binary.LittleEndian, m.LEFT) 6206 binary.Write(data, binary.LittleEndian, m.RIGHT) 6207 binary.Write(data, binary.LittleEndian, m.SENSOR_ID) 6208 binary.Write(data, binary.LittleEndian, m.QUALITY) 6209 return data.Bytes() 6210 } 6211 6212 // Decode accepts a packed byte array and populates the fields of the OmnidirectionalFlow 6213 func (m *OmnidirectionalFlow) Decode(buf []byte) { 6214 data := bytes.NewBuffer(buf) 6215 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 6216 binary.Read(data, binary.LittleEndian, &m.FRONT_DISTANCE_M) 6217 binary.Read(data, binary.LittleEndian, &m.LEFT) 6218 binary.Read(data, binary.LittleEndian, &m.RIGHT) 6219 binary.Read(data, binary.LittleEndian, &m.SENSOR_ID) 6220 binary.Read(data, binary.LittleEndian, &m.QUALITY) 6221 } 6222 6223 const ( 6224 MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_left_LEN = 10 6225 MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_right_LEN = 10 6226 ) 6227 6228 // 6229 // MESSAGE HIL_SENSOR 6230 // 6231 // MAVLINK_MSG_ID_HIL_SENSOR 107 6232 // 6233 // MAVLINK_MSG_ID_HIL_SENSOR_LEN 64 6234 // 6235 // MAVLINK_MSG_ID_HIL_SENSOR_CRC 108 6236 // 6237 // 6238 type HilSensor struct { 6239 TIME_USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) 6240 XACC float32 // X acceleration (m/s^2) 6241 YACC float32 // Y acceleration (m/s^2) 6242 ZACC float32 // Z acceleration (m/s^2) 6243 XGYRO float32 // Angular speed around X axis in body frame (rad / sec) 6244 YGYRO float32 // Angular speed around Y axis in body frame (rad / sec) 6245 ZGYRO float32 // Angular speed around Z axis in body frame (rad / sec) 6246 XMAG float32 // X Magnetic field (Gauss) 6247 YMAG float32 // Y Magnetic field (Gauss) 6248 ZMAG float32 // Z Magnetic field (Gauss) 6249 ABS_PRESSURE float32 // Absolute pressure in millibar 6250 DIFF_PRESSURE float32 // Differential pressure (airspeed) in millibar 6251 PRESSURE_ALT float32 // Altitude calculated from pressure 6252 TEMPERATURE float32 // Temperature in degrees celsius 6253 FIELDS_UPDATED uint32 // Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature 6254 } 6255 6256 // NewHilSensor returns a new HilSensor 6257 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 { 6258 m := HilSensor{} 6259 m.TIME_USEC = TIME_USEC 6260 m.XACC = XACC 6261 m.YACC = YACC 6262 m.ZACC = ZACC 6263 m.XGYRO = XGYRO 6264 m.YGYRO = YGYRO 6265 m.ZGYRO = ZGYRO 6266 m.XMAG = XMAG 6267 m.YMAG = YMAG 6268 m.ZMAG = ZMAG 6269 m.ABS_PRESSURE = ABS_PRESSURE 6270 m.DIFF_PRESSURE = DIFF_PRESSURE 6271 m.PRESSURE_ALT = PRESSURE_ALT 6272 m.TEMPERATURE = TEMPERATURE 6273 m.FIELDS_UPDATED = FIELDS_UPDATED 6274 return &m 6275 } 6276 6277 // Id returns the HilSensor Message ID 6278 func (*HilSensor) Id() uint8 { 6279 return 107 6280 } 6281 6282 // Len returns the HilSensor Message Length 6283 func (*HilSensor) Len() uint8 { 6284 return 64 6285 } 6286 6287 // Crc returns the HilSensor Message CRC 6288 func (*HilSensor) Crc() uint8 { 6289 return 108 6290 } 6291 6292 // Pack returns a packed byte array which represents a HilSensor payload 6293 func (m *HilSensor) Pack() []byte { 6294 data := new(bytes.Buffer) 6295 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 6296 binary.Write(data, binary.LittleEndian, m.XACC) 6297 binary.Write(data, binary.LittleEndian, m.YACC) 6298 binary.Write(data, binary.LittleEndian, m.ZACC) 6299 binary.Write(data, binary.LittleEndian, m.XGYRO) 6300 binary.Write(data, binary.LittleEndian, m.YGYRO) 6301 binary.Write(data, binary.LittleEndian, m.ZGYRO) 6302 binary.Write(data, binary.LittleEndian, m.XMAG) 6303 binary.Write(data, binary.LittleEndian, m.YMAG) 6304 binary.Write(data, binary.LittleEndian, m.ZMAG) 6305 binary.Write(data, binary.LittleEndian, m.ABS_PRESSURE) 6306 binary.Write(data, binary.LittleEndian, m.DIFF_PRESSURE) 6307 binary.Write(data, binary.LittleEndian, m.PRESSURE_ALT) 6308 binary.Write(data, binary.LittleEndian, m.TEMPERATURE) 6309 binary.Write(data, binary.LittleEndian, m.FIELDS_UPDATED) 6310 return data.Bytes() 6311 } 6312 6313 // Decode accepts a packed byte array and populates the fields of the HilSensor 6314 func (m *HilSensor) Decode(buf []byte) { 6315 data := bytes.NewBuffer(buf) 6316 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 6317 binary.Read(data, binary.LittleEndian, &m.XACC) 6318 binary.Read(data, binary.LittleEndian, &m.YACC) 6319 binary.Read(data, binary.LittleEndian, &m.ZACC) 6320 binary.Read(data, binary.LittleEndian, &m.XGYRO) 6321 binary.Read(data, binary.LittleEndian, &m.YGYRO) 6322 binary.Read(data, binary.LittleEndian, &m.ZGYRO) 6323 binary.Read(data, binary.LittleEndian, &m.XMAG) 6324 binary.Read(data, binary.LittleEndian, &m.YMAG) 6325 binary.Read(data, binary.LittleEndian, &m.ZMAG) 6326 binary.Read(data, binary.LittleEndian, &m.ABS_PRESSURE) 6327 binary.Read(data, binary.LittleEndian, &m.DIFF_PRESSURE) 6328 binary.Read(data, binary.LittleEndian, &m.PRESSURE_ALT) 6329 binary.Read(data, binary.LittleEndian, &m.TEMPERATURE) 6330 binary.Read(data, binary.LittleEndian, &m.FIELDS_UPDATED) 6331 } 6332 6333 // 6334 // MESSAGE SIM_STATE 6335 // 6336 // MAVLINK_MSG_ID_SIM_STATE 108 6337 // 6338 // MAVLINK_MSG_ID_SIM_STATE_LEN 84 6339 // 6340 // MAVLINK_MSG_ID_SIM_STATE_CRC 32 6341 // 6342 // 6343 type SimState struct { 6344 Q1 float32 // True attitude quaternion component 1, w (1 in null-rotation) 6345 Q2 float32 // True attitude quaternion component 2, x (0 in null-rotation) 6346 Q3 float32 // True attitude quaternion component 3, y (0 in null-rotation) 6347 Q4 float32 // True attitude quaternion component 4, z (0 in null-rotation) 6348 ROLL float32 // Attitude roll expressed as Euler angles, not recommended except for human-readable outputs 6349 PITCH float32 // Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs 6350 YAW float32 // Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs 6351 XACC float32 // X acceleration m/s/s 6352 YACC float32 // Y acceleration m/s/s 6353 ZACC float32 // Z acceleration m/s/s 6354 XGYRO float32 // Angular speed around X axis rad/s 6355 YGYRO float32 // Angular speed around Y axis rad/s 6356 ZGYRO float32 // Angular speed around Z axis rad/s 6357 LAT float32 // Latitude in degrees 6358 LON float32 // Longitude in degrees 6359 ALT float32 // Altitude in meters 6360 STD_DEV_HORZ float32 // Horizontal position standard deviation 6361 STD_DEV_VERT float32 // Vertical position standard deviation 6362 VN float32 // True velocity in m/s in NORTH direction in earth-fixed NED frame 6363 VE float32 // True velocity in m/s in EAST direction in earth-fixed NED frame 6364 VD float32 // True velocity in m/s in DOWN direction in earth-fixed NED frame 6365 } 6366 6367 // NewSimState returns a new SimState 6368 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 { 6369 m := SimState{} 6370 m.Q1 = Q1 6371 m.Q2 = Q2 6372 m.Q3 = Q3 6373 m.Q4 = Q4 6374 m.ROLL = ROLL 6375 m.PITCH = PITCH 6376 m.YAW = YAW 6377 m.XACC = XACC 6378 m.YACC = YACC 6379 m.ZACC = ZACC 6380 m.XGYRO = XGYRO 6381 m.YGYRO = YGYRO 6382 m.ZGYRO = ZGYRO 6383 m.LAT = LAT 6384 m.LON = LON 6385 m.ALT = ALT 6386 m.STD_DEV_HORZ = STD_DEV_HORZ 6387 m.STD_DEV_VERT = STD_DEV_VERT 6388 m.VN = VN 6389 m.VE = VE 6390 m.VD = VD 6391 return &m 6392 } 6393 6394 // Id returns the SimState Message ID 6395 func (*SimState) Id() uint8 { 6396 return 108 6397 } 6398 6399 // Len returns the SimState Message Length 6400 func (*SimState) Len() uint8 { 6401 return 84 6402 } 6403 6404 // Crc returns the SimState Message CRC 6405 func (*SimState) Crc() uint8 { 6406 return 32 6407 } 6408 6409 // Pack returns a packed byte array which represents a SimState payload 6410 func (m *SimState) Pack() []byte { 6411 data := new(bytes.Buffer) 6412 binary.Write(data, binary.LittleEndian, m.Q1) 6413 binary.Write(data, binary.LittleEndian, m.Q2) 6414 binary.Write(data, binary.LittleEndian, m.Q3) 6415 binary.Write(data, binary.LittleEndian, m.Q4) 6416 binary.Write(data, binary.LittleEndian, m.ROLL) 6417 binary.Write(data, binary.LittleEndian, m.PITCH) 6418 binary.Write(data, binary.LittleEndian, m.YAW) 6419 binary.Write(data, binary.LittleEndian, m.XACC) 6420 binary.Write(data, binary.LittleEndian, m.YACC) 6421 binary.Write(data, binary.LittleEndian, m.ZACC) 6422 binary.Write(data, binary.LittleEndian, m.XGYRO) 6423 binary.Write(data, binary.LittleEndian, m.YGYRO) 6424 binary.Write(data, binary.LittleEndian, m.ZGYRO) 6425 binary.Write(data, binary.LittleEndian, m.LAT) 6426 binary.Write(data, binary.LittleEndian, m.LON) 6427 binary.Write(data, binary.LittleEndian, m.ALT) 6428 binary.Write(data, binary.LittleEndian, m.STD_DEV_HORZ) 6429 binary.Write(data, binary.LittleEndian, m.STD_DEV_VERT) 6430 binary.Write(data, binary.LittleEndian, m.VN) 6431 binary.Write(data, binary.LittleEndian, m.VE) 6432 binary.Write(data, binary.LittleEndian, m.VD) 6433 return data.Bytes() 6434 } 6435 6436 // Decode accepts a packed byte array and populates the fields of the SimState 6437 func (m *SimState) Decode(buf []byte) { 6438 data := bytes.NewBuffer(buf) 6439 binary.Read(data, binary.LittleEndian, &m.Q1) 6440 binary.Read(data, binary.LittleEndian, &m.Q2) 6441 binary.Read(data, binary.LittleEndian, &m.Q3) 6442 binary.Read(data, binary.LittleEndian, &m.Q4) 6443 binary.Read(data, binary.LittleEndian, &m.ROLL) 6444 binary.Read(data, binary.LittleEndian, &m.PITCH) 6445 binary.Read(data, binary.LittleEndian, &m.YAW) 6446 binary.Read(data, binary.LittleEndian, &m.XACC) 6447 binary.Read(data, binary.LittleEndian, &m.YACC) 6448 binary.Read(data, binary.LittleEndian, &m.ZACC) 6449 binary.Read(data, binary.LittleEndian, &m.XGYRO) 6450 binary.Read(data, binary.LittleEndian, &m.YGYRO) 6451 binary.Read(data, binary.LittleEndian, &m.ZGYRO) 6452 binary.Read(data, binary.LittleEndian, &m.LAT) 6453 binary.Read(data, binary.LittleEndian, &m.LON) 6454 binary.Read(data, binary.LittleEndian, &m.ALT) 6455 binary.Read(data, binary.LittleEndian, &m.STD_DEV_HORZ) 6456 binary.Read(data, binary.LittleEndian, &m.STD_DEV_VERT) 6457 binary.Read(data, binary.LittleEndian, &m.VN) 6458 binary.Read(data, binary.LittleEndian, &m.VE) 6459 binary.Read(data, binary.LittleEndian, &m.VD) 6460 } 6461 6462 // 6463 // MESSAGE RADIO_STATUS 6464 // 6465 // MAVLINK_MSG_ID_RADIO_STATUS 109 6466 // 6467 // MAVLINK_MSG_ID_RADIO_STATUS_LEN 9 6468 // 6469 // MAVLINK_MSG_ID_RADIO_STATUS_CRC 185 6470 // 6471 // 6472 type RadioStatus struct { 6473 RXERRORS uint16 // receive errors 6474 FIXED uint16 // count of error corrected packets 6475 RSSI uint8 // local signal strength 6476 REMRSSI uint8 // remote signal strength 6477 TXBUF uint8 // how full the tx buffer is as a percentage 6478 NOISE uint8 // background noise level 6479 REMNOISE uint8 // remote background noise level 6480 } 6481 6482 // NewRadioStatus returns a new RadioStatus 6483 func NewRadioStatus(RXERRORS uint16, FIXED uint16, RSSI uint8, REMRSSI uint8, TXBUF uint8, NOISE uint8, REMNOISE uint8) *RadioStatus { 6484 m := RadioStatus{} 6485 m.RXERRORS = RXERRORS 6486 m.FIXED = FIXED 6487 m.RSSI = RSSI 6488 m.REMRSSI = REMRSSI 6489 m.TXBUF = TXBUF 6490 m.NOISE = NOISE 6491 m.REMNOISE = REMNOISE 6492 return &m 6493 } 6494 6495 // Id returns the RadioStatus Message ID 6496 func (*RadioStatus) Id() uint8 { 6497 return 109 6498 } 6499 6500 // Len returns the RadioStatus Message Length 6501 func (*RadioStatus) Len() uint8 { 6502 return 9 6503 } 6504 6505 // Crc returns the RadioStatus Message CRC 6506 func (*RadioStatus) Crc() uint8 { 6507 return 185 6508 } 6509 6510 // Pack returns a packed byte array which represents a RadioStatus payload 6511 func (m *RadioStatus) Pack() []byte { 6512 data := new(bytes.Buffer) 6513 binary.Write(data, binary.LittleEndian, m.RXERRORS) 6514 binary.Write(data, binary.LittleEndian, m.FIXED) 6515 binary.Write(data, binary.LittleEndian, m.RSSI) 6516 binary.Write(data, binary.LittleEndian, m.REMRSSI) 6517 binary.Write(data, binary.LittleEndian, m.TXBUF) 6518 binary.Write(data, binary.LittleEndian, m.NOISE) 6519 binary.Write(data, binary.LittleEndian, m.REMNOISE) 6520 return data.Bytes() 6521 } 6522 6523 // Decode accepts a packed byte array and populates the fields of the RadioStatus 6524 func (m *RadioStatus) Decode(buf []byte) { 6525 data := bytes.NewBuffer(buf) 6526 binary.Read(data, binary.LittleEndian, &m.RXERRORS) 6527 binary.Read(data, binary.LittleEndian, &m.FIXED) 6528 binary.Read(data, binary.LittleEndian, &m.RSSI) 6529 binary.Read(data, binary.LittleEndian, &m.REMRSSI) 6530 binary.Read(data, binary.LittleEndian, &m.TXBUF) 6531 binary.Read(data, binary.LittleEndian, &m.NOISE) 6532 binary.Read(data, binary.LittleEndian, &m.REMNOISE) 6533 } 6534 6535 // 6536 // MESSAGE FILE_TRANSFER_START 6537 // 6538 // MAVLINK_MSG_ID_FILE_TRANSFER_START 110 6539 // 6540 // MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN 254 6541 // 6542 // MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC 235 6543 // 6544 // 6545 type FileTransferStart struct { 6546 TRANSFER_UID uint64 // Unique transfer ID 6547 FILE_SIZE uint32 // File size in bytes 6548 DEST_PATH [240]uint8 // Destination path 6549 DIRECTION uint8 // Transfer direction: 0: from requester, 1: to requester 6550 FLAGS uint8 // RESERVED 6551 } 6552 6553 // NewFileTransferStart returns a new FileTransferStart 6554 func NewFileTransferStart(TRANSFER_UID uint64, FILE_SIZE uint32, DEST_PATH [240]uint8, DIRECTION uint8, FLAGS uint8) *FileTransferStart { 6555 m := FileTransferStart{} 6556 m.TRANSFER_UID = TRANSFER_UID 6557 m.FILE_SIZE = FILE_SIZE 6558 m.DEST_PATH = DEST_PATH 6559 m.DIRECTION = DIRECTION 6560 m.FLAGS = FLAGS 6561 return &m 6562 } 6563 6564 // Id returns the FileTransferStart Message ID 6565 func (*FileTransferStart) Id() uint8 { 6566 return 110 6567 } 6568 6569 // Len returns the FileTransferStart Message Length 6570 func (*FileTransferStart) Len() uint8 { 6571 return 254 6572 } 6573 6574 // Crc returns the FileTransferStart Message CRC 6575 func (*FileTransferStart) Crc() uint8 { 6576 return 235 6577 } 6578 6579 // Pack returns a packed byte array which represents a FileTransferStart payload 6580 func (m *FileTransferStart) Pack() []byte { 6581 data := new(bytes.Buffer) 6582 binary.Write(data, binary.LittleEndian, m.TRANSFER_UID) 6583 binary.Write(data, binary.LittleEndian, m.FILE_SIZE) 6584 binary.Write(data, binary.LittleEndian, m.DEST_PATH) 6585 binary.Write(data, binary.LittleEndian, m.DIRECTION) 6586 binary.Write(data, binary.LittleEndian, m.FLAGS) 6587 return data.Bytes() 6588 } 6589 6590 // Decode accepts a packed byte array and populates the fields of the FileTransferStart 6591 func (m *FileTransferStart) Decode(buf []byte) { 6592 data := bytes.NewBuffer(buf) 6593 binary.Read(data, binary.LittleEndian, &m.TRANSFER_UID) 6594 binary.Read(data, binary.LittleEndian, &m.FILE_SIZE) 6595 binary.Read(data, binary.LittleEndian, &m.DEST_PATH) 6596 binary.Read(data, binary.LittleEndian, &m.DIRECTION) 6597 binary.Read(data, binary.LittleEndian, &m.FLAGS) 6598 } 6599 6600 const ( 6601 MAVLINK_MSG_FILE_TRANSFER_START_FIELD_dest_path_LEN = 240 6602 ) 6603 6604 // 6605 // MESSAGE FILE_TRANSFER_DIR_LIST 6606 // 6607 // MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST 111 6608 // 6609 // MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN 249 6610 // 6611 // MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC 93 6612 // 6613 // 6614 type FileTransferDirList struct { 6615 TRANSFER_UID uint64 // Unique transfer ID 6616 DIR_PATH [240]uint8 // Directory path to list 6617 FLAGS uint8 // RESERVED 6618 } 6619 6620 // NewFileTransferDirList returns a new FileTransferDirList 6621 func NewFileTransferDirList(TRANSFER_UID uint64, DIR_PATH [240]uint8, FLAGS uint8) *FileTransferDirList { 6622 m := FileTransferDirList{} 6623 m.TRANSFER_UID = TRANSFER_UID 6624 m.DIR_PATH = DIR_PATH 6625 m.FLAGS = FLAGS 6626 return &m 6627 } 6628 6629 // Id returns the FileTransferDirList Message ID 6630 func (*FileTransferDirList) Id() uint8 { 6631 return 111 6632 } 6633 6634 // Len returns the FileTransferDirList Message Length 6635 func (*FileTransferDirList) Len() uint8 { 6636 return 249 6637 } 6638 6639 // Crc returns the FileTransferDirList Message CRC 6640 func (*FileTransferDirList) Crc() uint8 { 6641 return 93 6642 } 6643 6644 // Pack returns a packed byte array which represents a FileTransferDirList payload 6645 func (m *FileTransferDirList) Pack() []byte { 6646 data := new(bytes.Buffer) 6647 binary.Write(data, binary.LittleEndian, m.TRANSFER_UID) 6648 binary.Write(data, binary.LittleEndian, m.DIR_PATH) 6649 binary.Write(data, binary.LittleEndian, m.FLAGS) 6650 return data.Bytes() 6651 } 6652 6653 // Decode accepts a packed byte array and populates the fields of the FileTransferDirList 6654 func (m *FileTransferDirList) Decode(buf []byte) { 6655 data := bytes.NewBuffer(buf) 6656 binary.Read(data, binary.LittleEndian, &m.TRANSFER_UID) 6657 binary.Read(data, binary.LittleEndian, &m.DIR_PATH) 6658 binary.Read(data, binary.LittleEndian, &m.FLAGS) 6659 } 6660 6661 const ( 6662 MAVLINK_MSG_FILE_TRANSFER_DIR_LIST_FIELD_dir_path_LEN = 240 6663 ) 6664 6665 // 6666 // MESSAGE FILE_TRANSFER_RES 6667 // 6668 // MAVLINK_MSG_ID_FILE_TRANSFER_RES 112 6669 // 6670 // MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN 9 6671 // 6672 // MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC 124 6673 // 6674 // 6675 type FileTransferRes struct { 6676 TRANSFER_UID uint64 // Unique transfer ID 6677 RESULT uint8 // 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device 6678 } 6679 6680 // NewFileTransferRes returns a new FileTransferRes 6681 func NewFileTransferRes(TRANSFER_UID uint64, RESULT uint8) *FileTransferRes { 6682 m := FileTransferRes{} 6683 m.TRANSFER_UID = TRANSFER_UID 6684 m.RESULT = RESULT 6685 return &m 6686 } 6687 6688 // Id returns the FileTransferRes Message ID 6689 func (*FileTransferRes) Id() uint8 { 6690 return 112 6691 } 6692 6693 // Len returns the FileTransferRes Message Length 6694 func (*FileTransferRes) Len() uint8 { 6695 return 9 6696 } 6697 6698 // Crc returns the FileTransferRes Message CRC 6699 func (*FileTransferRes) Crc() uint8 { 6700 return 124 6701 } 6702 6703 // Pack returns a packed byte array which represents a FileTransferRes payload 6704 func (m *FileTransferRes) Pack() []byte { 6705 data := new(bytes.Buffer) 6706 binary.Write(data, binary.LittleEndian, m.TRANSFER_UID) 6707 binary.Write(data, binary.LittleEndian, m.RESULT) 6708 return data.Bytes() 6709 } 6710 6711 // Decode accepts a packed byte array and populates the fields of the FileTransferRes 6712 func (m *FileTransferRes) Decode(buf []byte) { 6713 data := bytes.NewBuffer(buf) 6714 binary.Read(data, binary.LittleEndian, &m.TRANSFER_UID) 6715 binary.Read(data, binary.LittleEndian, &m.RESULT) 6716 } 6717 6718 // 6719 // MESSAGE HIL_GPS 6720 // 6721 // MAVLINK_MSG_ID_HIL_GPS 113 6722 // 6723 // MAVLINK_MSG_ID_HIL_GPS_LEN 36 6724 // 6725 // MAVLINK_MSG_ID_HIL_GPS_CRC 124 6726 // 6727 // 6728 type HilGps struct { 6729 TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) 6730 LAT int32 // Latitude (WGS84), in degrees * 1E7 6731 LON int32 // Longitude (WGS84), in degrees * 1E7 6732 ALT int32 // Altitude (WGS84), in meters * 1000 (positive for up) 6733 EPH uint16 // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 6734 EPV uint16 // GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 6735 VEL uint16 // GPS ground speed (m/s * 100). If unknown, set to: 65535 6736 VN int16 // GPS velocity in cm/s in NORTH direction in earth-fixed NED frame 6737 VE int16 // GPS velocity in cm/s in EAST direction in earth-fixed NED frame 6738 VD int16 // GPS velocity in cm/s in DOWN direction in earth-fixed NED frame 6739 COG uint16 // Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 6740 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. 6741 SATELLITES_VISIBLE uint8 // Number of satellites visible. If unknown, set to 255 6742 } 6743 6744 // NewHilGps returns a new HilGps 6745 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 { 6746 m := HilGps{} 6747 m.TIME_USEC = TIME_USEC 6748 m.LAT = LAT 6749 m.LON = LON 6750 m.ALT = ALT 6751 m.EPH = EPH 6752 m.EPV = EPV 6753 m.VEL = VEL 6754 m.VN = VN 6755 m.VE = VE 6756 m.VD = VD 6757 m.COG = COG 6758 m.FIX_TYPE = FIX_TYPE 6759 m.SATELLITES_VISIBLE = SATELLITES_VISIBLE 6760 return &m 6761 } 6762 6763 // Id returns the HilGps Message ID 6764 func (*HilGps) Id() uint8 { 6765 return 113 6766 } 6767 6768 // Len returns the HilGps Message Length 6769 func (*HilGps) Len() uint8 { 6770 return 36 6771 } 6772 6773 // Crc returns the HilGps Message CRC 6774 func (*HilGps) Crc() uint8 { 6775 return 124 6776 } 6777 6778 // Pack returns a packed byte array which represents a HilGps payload 6779 func (m *HilGps) Pack() []byte { 6780 data := new(bytes.Buffer) 6781 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 6782 binary.Write(data, binary.LittleEndian, m.LAT) 6783 binary.Write(data, binary.LittleEndian, m.LON) 6784 binary.Write(data, binary.LittleEndian, m.ALT) 6785 binary.Write(data, binary.LittleEndian, m.EPH) 6786 binary.Write(data, binary.LittleEndian, m.EPV) 6787 binary.Write(data, binary.LittleEndian, m.VEL) 6788 binary.Write(data, binary.LittleEndian, m.VN) 6789 binary.Write(data, binary.LittleEndian, m.VE) 6790 binary.Write(data, binary.LittleEndian, m.VD) 6791 binary.Write(data, binary.LittleEndian, m.COG) 6792 binary.Write(data, binary.LittleEndian, m.FIX_TYPE) 6793 binary.Write(data, binary.LittleEndian, m.SATELLITES_VISIBLE) 6794 return data.Bytes() 6795 } 6796 6797 // Decode accepts a packed byte array and populates the fields of the HilGps 6798 func (m *HilGps) Decode(buf []byte) { 6799 data := bytes.NewBuffer(buf) 6800 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 6801 binary.Read(data, binary.LittleEndian, &m.LAT) 6802 binary.Read(data, binary.LittleEndian, &m.LON) 6803 binary.Read(data, binary.LittleEndian, &m.ALT) 6804 binary.Read(data, binary.LittleEndian, &m.EPH) 6805 binary.Read(data, binary.LittleEndian, &m.EPV) 6806 binary.Read(data, binary.LittleEndian, &m.VEL) 6807 binary.Read(data, binary.LittleEndian, &m.VN) 6808 binary.Read(data, binary.LittleEndian, &m.VE) 6809 binary.Read(data, binary.LittleEndian, &m.VD) 6810 binary.Read(data, binary.LittleEndian, &m.COG) 6811 binary.Read(data, binary.LittleEndian, &m.FIX_TYPE) 6812 binary.Read(data, binary.LittleEndian, &m.SATELLITES_VISIBLE) 6813 } 6814 6815 // 6816 // MESSAGE HIL_OPTICAL_FLOW 6817 // 6818 // MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114 6819 // 6820 // MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 26 6821 // 6822 // MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 119 6823 // 6824 // 6825 type HilOpticalFlow struct { 6826 TIME_USEC uint64 // Timestamp (UNIX) 6827 FLOW_COMP_M_X float32 // Flow in meters in x-sensor direction, angular-speed compensated 6828 FLOW_COMP_M_Y float32 // Flow in meters in y-sensor direction, angular-speed compensated 6829 GROUND_DISTANCE float32 // Ground distance in meters. Positive value: distance known. Negative value: Unknown distance 6830 FLOW_X int16 // Flow in pixels in x-sensor direction 6831 FLOW_Y int16 // Flow in pixels in y-sensor direction 6832 SENSOR_ID uint8 // Sensor ID 6833 QUALITY uint8 // Optical flow quality / confidence. 0: bad, 255: maximum quality 6834 } 6835 6836 // NewHilOpticalFlow returns a new HilOpticalFlow 6837 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 { 6838 m := HilOpticalFlow{} 6839 m.TIME_USEC = TIME_USEC 6840 m.FLOW_COMP_M_X = FLOW_COMP_M_X 6841 m.FLOW_COMP_M_Y = FLOW_COMP_M_Y 6842 m.GROUND_DISTANCE = GROUND_DISTANCE 6843 m.FLOW_X = FLOW_X 6844 m.FLOW_Y = FLOW_Y 6845 m.SENSOR_ID = SENSOR_ID 6846 m.QUALITY = QUALITY 6847 return &m 6848 } 6849 6850 // Id returns the HilOpticalFlow Message ID 6851 func (*HilOpticalFlow) Id() uint8 { 6852 return 114 6853 } 6854 6855 // Len returns the HilOpticalFlow Message Length 6856 func (*HilOpticalFlow) Len() uint8 { 6857 return 26 6858 } 6859 6860 // Crc returns the HilOpticalFlow Message CRC 6861 func (*HilOpticalFlow) Crc() uint8 { 6862 return 119 6863 } 6864 6865 // Pack returns a packed byte array which represents a HilOpticalFlow payload 6866 func (m *HilOpticalFlow) Pack() []byte { 6867 data := new(bytes.Buffer) 6868 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 6869 binary.Write(data, binary.LittleEndian, m.FLOW_COMP_M_X) 6870 binary.Write(data, binary.LittleEndian, m.FLOW_COMP_M_Y) 6871 binary.Write(data, binary.LittleEndian, m.GROUND_DISTANCE) 6872 binary.Write(data, binary.LittleEndian, m.FLOW_X) 6873 binary.Write(data, binary.LittleEndian, m.FLOW_Y) 6874 binary.Write(data, binary.LittleEndian, m.SENSOR_ID) 6875 binary.Write(data, binary.LittleEndian, m.QUALITY) 6876 return data.Bytes() 6877 } 6878 6879 // Decode accepts a packed byte array and populates the fields of the HilOpticalFlow 6880 func (m *HilOpticalFlow) Decode(buf []byte) { 6881 data := bytes.NewBuffer(buf) 6882 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 6883 binary.Read(data, binary.LittleEndian, &m.FLOW_COMP_M_X) 6884 binary.Read(data, binary.LittleEndian, &m.FLOW_COMP_M_Y) 6885 binary.Read(data, binary.LittleEndian, &m.GROUND_DISTANCE) 6886 binary.Read(data, binary.LittleEndian, &m.FLOW_X) 6887 binary.Read(data, binary.LittleEndian, &m.FLOW_Y) 6888 binary.Read(data, binary.LittleEndian, &m.SENSOR_ID) 6889 binary.Read(data, binary.LittleEndian, &m.QUALITY) 6890 } 6891 6892 // 6893 // MESSAGE HIL_STATE_QUATERNION 6894 // 6895 // MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115 6896 // 6897 // MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64 6898 // 6899 // MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4 6900 // 6901 // 6902 type HilStateQuaternion struct { 6903 TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) 6904 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) 6905 ROLLSPEED float32 // Body frame roll / phi angular speed (rad/s) 6906 PITCHSPEED float32 // Body frame pitch / theta angular speed (rad/s) 6907 YAWSPEED float32 // Body frame yaw / psi angular speed (rad/s) 6908 LAT int32 // Latitude, expressed as * 1E7 6909 LON int32 // Longitude, expressed as * 1E7 6910 ALT int32 // Altitude in meters, expressed as * 1000 (millimeters) 6911 VX int16 // Ground X Speed (Latitude), expressed as m/s * 100 6912 VY int16 // Ground Y Speed (Longitude), expressed as m/s * 100 6913 VZ int16 // Ground Z Speed (Altitude), expressed as m/s * 100 6914 IND_AIRSPEED uint16 // Indicated airspeed, expressed as m/s * 100 6915 TRUE_AIRSPEED uint16 // True airspeed, expressed as m/s * 100 6916 XACC int16 // X acceleration (mg) 6917 YACC int16 // Y acceleration (mg) 6918 ZACC int16 // Z acceleration (mg) 6919 } 6920 6921 // NewHilStateQuaternion returns a new HilStateQuaternion 6922 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 { 6923 m := HilStateQuaternion{} 6924 m.TIME_USEC = TIME_USEC 6925 m.ATTITUDE_QUATERNION = ATTITUDE_QUATERNION 6926 m.ROLLSPEED = ROLLSPEED 6927 m.PITCHSPEED = PITCHSPEED 6928 m.YAWSPEED = YAWSPEED 6929 m.LAT = LAT 6930 m.LON = LON 6931 m.ALT = ALT 6932 m.VX = VX 6933 m.VY = VY 6934 m.VZ = VZ 6935 m.IND_AIRSPEED = IND_AIRSPEED 6936 m.TRUE_AIRSPEED = TRUE_AIRSPEED 6937 m.XACC = XACC 6938 m.YACC = YACC 6939 m.ZACC = ZACC 6940 return &m 6941 } 6942 6943 // Id returns the HilStateQuaternion Message ID 6944 func (*HilStateQuaternion) Id() uint8 { 6945 return 115 6946 } 6947 6948 // Len returns the HilStateQuaternion Message Length 6949 func (*HilStateQuaternion) Len() uint8 { 6950 return 64 6951 } 6952 6953 // Crc returns the HilStateQuaternion Message CRC 6954 func (*HilStateQuaternion) Crc() uint8 { 6955 return 4 6956 } 6957 6958 // Pack returns a packed byte array which represents a HilStateQuaternion payload 6959 func (m *HilStateQuaternion) Pack() []byte { 6960 data := new(bytes.Buffer) 6961 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 6962 binary.Write(data, binary.LittleEndian, m.ATTITUDE_QUATERNION) 6963 binary.Write(data, binary.LittleEndian, m.ROLLSPEED) 6964 binary.Write(data, binary.LittleEndian, m.PITCHSPEED) 6965 binary.Write(data, binary.LittleEndian, m.YAWSPEED) 6966 binary.Write(data, binary.LittleEndian, m.LAT) 6967 binary.Write(data, binary.LittleEndian, m.LON) 6968 binary.Write(data, binary.LittleEndian, m.ALT) 6969 binary.Write(data, binary.LittleEndian, m.VX) 6970 binary.Write(data, binary.LittleEndian, m.VY) 6971 binary.Write(data, binary.LittleEndian, m.VZ) 6972 binary.Write(data, binary.LittleEndian, m.IND_AIRSPEED) 6973 binary.Write(data, binary.LittleEndian, m.TRUE_AIRSPEED) 6974 binary.Write(data, binary.LittleEndian, m.XACC) 6975 binary.Write(data, binary.LittleEndian, m.YACC) 6976 binary.Write(data, binary.LittleEndian, m.ZACC) 6977 return data.Bytes() 6978 } 6979 6980 // Decode accepts a packed byte array and populates the fields of the HilStateQuaternion 6981 func (m *HilStateQuaternion) Decode(buf []byte) { 6982 data := bytes.NewBuffer(buf) 6983 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 6984 binary.Read(data, binary.LittleEndian, &m.ATTITUDE_QUATERNION) 6985 binary.Read(data, binary.LittleEndian, &m.ROLLSPEED) 6986 binary.Read(data, binary.LittleEndian, &m.PITCHSPEED) 6987 binary.Read(data, binary.LittleEndian, &m.YAWSPEED) 6988 binary.Read(data, binary.LittleEndian, &m.LAT) 6989 binary.Read(data, binary.LittleEndian, &m.LON) 6990 binary.Read(data, binary.LittleEndian, &m.ALT) 6991 binary.Read(data, binary.LittleEndian, &m.VX) 6992 binary.Read(data, binary.LittleEndian, &m.VY) 6993 binary.Read(data, binary.LittleEndian, &m.VZ) 6994 binary.Read(data, binary.LittleEndian, &m.IND_AIRSPEED) 6995 binary.Read(data, binary.LittleEndian, &m.TRUE_AIRSPEED) 6996 binary.Read(data, binary.LittleEndian, &m.XACC) 6997 binary.Read(data, binary.LittleEndian, &m.YACC) 6998 binary.Read(data, binary.LittleEndian, &m.ZACC) 6999 } 7000 7001 const ( 7002 MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_attitude_quaternion_LEN = 4 7003 ) 7004 7005 // 7006 // MESSAGE SCALED_IMU2 7007 // 7008 // MAVLINK_MSG_ID_SCALED_IMU2 116 7009 // 7010 // MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 7011 // 7012 // MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 7013 // 7014 // 7015 type ScaledImu2 struct { 7016 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 7017 XACC int16 // X acceleration (mg) 7018 YACC int16 // Y acceleration (mg) 7019 ZACC int16 // Z acceleration (mg) 7020 XGYRO int16 // Angular speed around X axis (millirad /sec) 7021 YGYRO int16 // Angular speed around Y axis (millirad /sec) 7022 ZGYRO int16 // Angular speed around Z axis (millirad /sec) 7023 XMAG int16 // X Magnetic field (milli tesla) 7024 YMAG int16 // Y Magnetic field (milli tesla) 7025 ZMAG int16 // Z Magnetic field (milli tesla) 7026 } 7027 7028 // NewScaledImu2 returns a new ScaledImu2 7029 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 { 7030 m := ScaledImu2{} 7031 m.TIME_BOOT_MS = TIME_BOOT_MS 7032 m.XACC = XACC 7033 m.YACC = YACC 7034 m.ZACC = ZACC 7035 m.XGYRO = XGYRO 7036 m.YGYRO = YGYRO 7037 m.ZGYRO = ZGYRO 7038 m.XMAG = XMAG 7039 m.YMAG = YMAG 7040 m.ZMAG = ZMAG 7041 return &m 7042 } 7043 7044 // Id returns the ScaledImu2 Message ID 7045 func (*ScaledImu2) Id() uint8 { 7046 return 116 7047 } 7048 7049 // Len returns the ScaledImu2 Message Length 7050 func (*ScaledImu2) Len() uint8 { 7051 return 22 7052 } 7053 7054 // Crc returns the ScaledImu2 Message CRC 7055 func (*ScaledImu2) Crc() uint8 { 7056 return 76 7057 } 7058 7059 // Pack returns a packed byte array which represents a ScaledImu2 payload 7060 func (m *ScaledImu2) Pack() []byte { 7061 data := new(bytes.Buffer) 7062 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 7063 binary.Write(data, binary.LittleEndian, m.XACC) 7064 binary.Write(data, binary.LittleEndian, m.YACC) 7065 binary.Write(data, binary.LittleEndian, m.ZACC) 7066 binary.Write(data, binary.LittleEndian, m.XGYRO) 7067 binary.Write(data, binary.LittleEndian, m.YGYRO) 7068 binary.Write(data, binary.LittleEndian, m.ZGYRO) 7069 binary.Write(data, binary.LittleEndian, m.XMAG) 7070 binary.Write(data, binary.LittleEndian, m.YMAG) 7071 binary.Write(data, binary.LittleEndian, m.ZMAG) 7072 return data.Bytes() 7073 } 7074 7075 // Decode accepts a packed byte array and populates the fields of the ScaledImu2 7076 func (m *ScaledImu2) Decode(buf []byte) { 7077 data := bytes.NewBuffer(buf) 7078 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 7079 binary.Read(data, binary.LittleEndian, &m.XACC) 7080 binary.Read(data, binary.LittleEndian, &m.YACC) 7081 binary.Read(data, binary.LittleEndian, &m.ZACC) 7082 binary.Read(data, binary.LittleEndian, &m.XGYRO) 7083 binary.Read(data, binary.LittleEndian, &m.YGYRO) 7084 binary.Read(data, binary.LittleEndian, &m.ZGYRO) 7085 binary.Read(data, binary.LittleEndian, &m.XMAG) 7086 binary.Read(data, binary.LittleEndian, &m.YMAG) 7087 binary.Read(data, binary.LittleEndian, &m.ZMAG) 7088 } 7089 7090 // 7091 // MESSAGE LOG_REQUEST_LIST 7092 // 7093 // MAVLINK_MSG_ID_LOG_REQUEST_LIST 117 7094 // 7095 // MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6 7096 // 7097 // MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC 128 7098 // 7099 // 7100 type LogRequestList struct { 7101 START uint16 // First log id (0 for first available) 7102 END uint16 // Last log id (0xffff for last available) 7103 TARGET_SYSTEM uint8 // System ID 7104 TARGET_COMPONENT uint8 // Component ID 7105 } 7106 7107 // NewLogRequestList returns a new LogRequestList 7108 func NewLogRequestList(START uint16, END uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *LogRequestList { 7109 m := LogRequestList{} 7110 m.START = START 7111 m.END = END 7112 m.TARGET_SYSTEM = TARGET_SYSTEM 7113 m.TARGET_COMPONENT = TARGET_COMPONENT 7114 return &m 7115 } 7116 7117 // Id returns the LogRequestList Message ID 7118 func (*LogRequestList) Id() uint8 { 7119 return 117 7120 } 7121 7122 // Len returns the LogRequestList Message Length 7123 func (*LogRequestList) Len() uint8 { 7124 return 6 7125 } 7126 7127 // Crc returns the LogRequestList Message CRC 7128 func (*LogRequestList) Crc() uint8 { 7129 return 128 7130 } 7131 7132 // Pack returns a packed byte array which represents a LogRequestList payload 7133 func (m *LogRequestList) Pack() []byte { 7134 data := new(bytes.Buffer) 7135 binary.Write(data, binary.LittleEndian, m.START) 7136 binary.Write(data, binary.LittleEndian, m.END) 7137 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 7138 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 7139 return data.Bytes() 7140 } 7141 7142 // Decode accepts a packed byte array and populates the fields of the LogRequestList 7143 func (m *LogRequestList) Decode(buf []byte) { 7144 data := bytes.NewBuffer(buf) 7145 binary.Read(data, binary.LittleEndian, &m.START) 7146 binary.Read(data, binary.LittleEndian, &m.END) 7147 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 7148 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 7149 } 7150 7151 // 7152 // MESSAGE LOG_ENTRY 7153 // 7154 // MAVLINK_MSG_ID_LOG_ENTRY 118 7155 // 7156 // MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 7157 // 7158 // MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 7159 // 7160 // 7161 type LogEntry struct { 7162 TIME_UTC uint32 // UTC timestamp of log in seconds since 1970, or 0 if not available 7163 SIZE uint32 // Size of the log (may be approximate) in bytes 7164 ID uint16 // Log id 7165 NUM_LOGS uint16 // Total number of logs 7166 LAST_LOG_NUM uint16 // High log number 7167 } 7168 7169 // NewLogEntry returns a new LogEntry 7170 func NewLogEntry(TIME_UTC uint32, SIZE uint32, ID uint16, NUM_LOGS uint16, LAST_LOG_NUM uint16) *LogEntry { 7171 m := LogEntry{} 7172 m.TIME_UTC = TIME_UTC 7173 m.SIZE = SIZE 7174 m.ID = ID 7175 m.NUM_LOGS = NUM_LOGS 7176 m.LAST_LOG_NUM = LAST_LOG_NUM 7177 return &m 7178 } 7179 7180 // Id returns the LogEntry Message ID 7181 func (*LogEntry) Id() uint8 { 7182 return 118 7183 } 7184 7185 // Len returns the LogEntry Message Length 7186 func (*LogEntry) Len() uint8 { 7187 return 14 7188 } 7189 7190 // Crc returns the LogEntry Message CRC 7191 func (*LogEntry) Crc() uint8 { 7192 return 56 7193 } 7194 7195 // Pack returns a packed byte array which represents a LogEntry payload 7196 func (m *LogEntry) Pack() []byte { 7197 data := new(bytes.Buffer) 7198 binary.Write(data, binary.LittleEndian, m.TIME_UTC) 7199 binary.Write(data, binary.LittleEndian, m.SIZE) 7200 binary.Write(data, binary.LittleEndian, m.ID) 7201 binary.Write(data, binary.LittleEndian, m.NUM_LOGS) 7202 binary.Write(data, binary.LittleEndian, m.LAST_LOG_NUM) 7203 return data.Bytes() 7204 } 7205 7206 // Decode accepts a packed byte array and populates the fields of the LogEntry 7207 func (m *LogEntry) Decode(buf []byte) { 7208 data := bytes.NewBuffer(buf) 7209 binary.Read(data, binary.LittleEndian, &m.TIME_UTC) 7210 binary.Read(data, binary.LittleEndian, &m.SIZE) 7211 binary.Read(data, binary.LittleEndian, &m.ID) 7212 binary.Read(data, binary.LittleEndian, &m.NUM_LOGS) 7213 binary.Read(data, binary.LittleEndian, &m.LAST_LOG_NUM) 7214 } 7215 7216 // 7217 // MESSAGE LOG_REQUEST_DATA 7218 // 7219 // MAVLINK_MSG_ID_LOG_REQUEST_DATA 119 7220 // 7221 // MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12 7222 // 7223 // MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116 7224 // 7225 // 7226 type LogRequestData struct { 7227 OFS uint32 // Offset into the log 7228 COUNT uint32 // Number of bytes 7229 ID uint16 // Log id (from LOG_ENTRY reply) 7230 TARGET_SYSTEM uint8 // System ID 7231 TARGET_COMPONENT uint8 // Component ID 7232 } 7233 7234 // NewLogRequestData returns a new LogRequestData 7235 func NewLogRequestData(OFS uint32, COUNT uint32, ID uint16, TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *LogRequestData { 7236 m := LogRequestData{} 7237 m.OFS = OFS 7238 m.COUNT = COUNT 7239 m.ID = ID 7240 m.TARGET_SYSTEM = TARGET_SYSTEM 7241 m.TARGET_COMPONENT = TARGET_COMPONENT 7242 return &m 7243 } 7244 7245 // Id returns the LogRequestData Message ID 7246 func (*LogRequestData) Id() uint8 { 7247 return 119 7248 } 7249 7250 // Len returns the LogRequestData Message Length 7251 func (*LogRequestData) Len() uint8 { 7252 return 12 7253 } 7254 7255 // Crc returns the LogRequestData Message CRC 7256 func (*LogRequestData) Crc() uint8 { 7257 return 116 7258 } 7259 7260 // Pack returns a packed byte array which represents a LogRequestData payload 7261 func (m *LogRequestData) Pack() []byte { 7262 data := new(bytes.Buffer) 7263 binary.Write(data, binary.LittleEndian, m.OFS) 7264 binary.Write(data, binary.LittleEndian, m.COUNT) 7265 binary.Write(data, binary.LittleEndian, m.ID) 7266 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 7267 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 7268 return data.Bytes() 7269 } 7270 7271 // Decode accepts a packed byte array and populates the fields of the LogRequestData 7272 func (m *LogRequestData) Decode(buf []byte) { 7273 data := bytes.NewBuffer(buf) 7274 binary.Read(data, binary.LittleEndian, &m.OFS) 7275 binary.Read(data, binary.LittleEndian, &m.COUNT) 7276 binary.Read(data, binary.LittleEndian, &m.ID) 7277 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 7278 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 7279 } 7280 7281 // 7282 // MESSAGE LOG_DATA 7283 // 7284 // MAVLINK_MSG_ID_LOG_DATA 120 7285 // 7286 // MAVLINK_MSG_ID_LOG_DATA_LEN 97 7287 // 7288 // MAVLINK_MSG_ID_LOG_DATA_CRC 134 7289 // 7290 // 7291 type LogData struct { 7292 OFS uint32 // Offset into the log 7293 ID uint16 // Log id (from LOG_ENTRY reply) 7294 COUNT uint8 // Number of bytes (zero for end of log) 7295 DATA [90]uint8 // log data 7296 } 7297 7298 // NewLogData returns a new LogData 7299 func NewLogData(OFS uint32, ID uint16, COUNT uint8, DATA [90]uint8) *LogData { 7300 m := LogData{} 7301 m.OFS = OFS 7302 m.ID = ID 7303 m.COUNT = COUNT 7304 m.DATA = DATA 7305 return &m 7306 } 7307 7308 // Id returns the LogData Message ID 7309 func (*LogData) Id() uint8 { 7310 return 120 7311 } 7312 7313 // Len returns the LogData Message Length 7314 func (*LogData) Len() uint8 { 7315 return 97 7316 } 7317 7318 // Crc returns the LogData Message CRC 7319 func (*LogData) Crc() uint8 { 7320 return 134 7321 } 7322 7323 // Pack returns a packed byte array which represents a LogData payload 7324 func (m *LogData) Pack() []byte { 7325 data := new(bytes.Buffer) 7326 binary.Write(data, binary.LittleEndian, m.OFS) 7327 binary.Write(data, binary.LittleEndian, m.ID) 7328 binary.Write(data, binary.LittleEndian, m.COUNT) 7329 binary.Write(data, binary.LittleEndian, m.DATA) 7330 return data.Bytes() 7331 } 7332 7333 // Decode accepts a packed byte array and populates the fields of the LogData 7334 func (m *LogData) Decode(buf []byte) { 7335 data := bytes.NewBuffer(buf) 7336 binary.Read(data, binary.LittleEndian, &m.OFS) 7337 binary.Read(data, binary.LittleEndian, &m.ID) 7338 binary.Read(data, binary.LittleEndian, &m.COUNT) 7339 binary.Read(data, binary.LittleEndian, &m.DATA) 7340 } 7341 7342 const ( 7343 MAVLINK_MSG_LOG_DATA_FIELD_data_LEN = 90 7344 ) 7345 7346 // 7347 // MESSAGE LOG_ERASE 7348 // 7349 // MAVLINK_MSG_ID_LOG_ERASE 121 7350 // 7351 // MAVLINK_MSG_ID_LOG_ERASE_LEN 2 7352 // 7353 // MAVLINK_MSG_ID_LOG_ERASE_CRC 237 7354 // 7355 // 7356 type LogErase struct { 7357 TARGET_SYSTEM uint8 // System ID 7358 TARGET_COMPONENT uint8 // Component ID 7359 } 7360 7361 // NewLogErase returns a new LogErase 7362 func NewLogErase(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *LogErase { 7363 m := LogErase{} 7364 m.TARGET_SYSTEM = TARGET_SYSTEM 7365 m.TARGET_COMPONENT = TARGET_COMPONENT 7366 return &m 7367 } 7368 7369 // Id returns the LogErase Message ID 7370 func (*LogErase) Id() uint8 { 7371 return 121 7372 } 7373 7374 // Len returns the LogErase Message Length 7375 func (*LogErase) Len() uint8 { 7376 return 2 7377 } 7378 7379 // Crc returns the LogErase Message CRC 7380 func (*LogErase) Crc() uint8 { 7381 return 237 7382 } 7383 7384 // Pack returns a packed byte array which represents a LogErase payload 7385 func (m *LogErase) Pack() []byte { 7386 data := new(bytes.Buffer) 7387 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 7388 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 7389 return data.Bytes() 7390 } 7391 7392 // Decode accepts a packed byte array and populates the fields of the LogErase 7393 func (m *LogErase) Decode(buf []byte) { 7394 data := bytes.NewBuffer(buf) 7395 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 7396 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 7397 } 7398 7399 // 7400 // MESSAGE LOG_REQUEST_END 7401 // 7402 // MAVLINK_MSG_ID_LOG_REQUEST_END 122 7403 // 7404 // MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2 7405 // 7406 // MAVLINK_MSG_ID_LOG_REQUEST_END_CRC 203 7407 // 7408 // 7409 type LogRequestEnd struct { 7410 TARGET_SYSTEM uint8 // System ID 7411 TARGET_COMPONENT uint8 // Component ID 7412 } 7413 7414 // NewLogRequestEnd returns a new LogRequestEnd 7415 func NewLogRequestEnd(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8) *LogRequestEnd { 7416 m := LogRequestEnd{} 7417 m.TARGET_SYSTEM = TARGET_SYSTEM 7418 m.TARGET_COMPONENT = TARGET_COMPONENT 7419 return &m 7420 } 7421 7422 // Id returns the LogRequestEnd Message ID 7423 func (*LogRequestEnd) Id() uint8 { 7424 return 122 7425 } 7426 7427 // Len returns the LogRequestEnd Message Length 7428 func (*LogRequestEnd) Len() uint8 { 7429 return 2 7430 } 7431 7432 // Crc returns the LogRequestEnd Message CRC 7433 func (*LogRequestEnd) Crc() uint8 { 7434 return 203 7435 } 7436 7437 // Pack returns a packed byte array which represents a LogRequestEnd payload 7438 func (m *LogRequestEnd) Pack() []byte { 7439 data := new(bytes.Buffer) 7440 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 7441 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 7442 return data.Bytes() 7443 } 7444 7445 // Decode accepts a packed byte array and populates the fields of the LogRequestEnd 7446 func (m *LogRequestEnd) Decode(buf []byte) { 7447 data := bytes.NewBuffer(buf) 7448 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 7449 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 7450 } 7451 7452 // 7453 // MESSAGE GPS_INJECT_DATA 7454 // 7455 // MAVLINK_MSG_ID_GPS_INJECT_DATA 123 7456 // 7457 // MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113 7458 // 7459 // MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250 7460 // 7461 // 7462 type GpsInjectData struct { 7463 TARGET_SYSTEM uint8 // System ID 7464 TARGET_COMPONENT uint8 // Component ID 7465 LEN uint8 // data length 7466 DATA [110]uint8 // raw data (110 is enough for 12 satellites of RTCMv2) 7467 } 7468 7469 // NewGpsInjectData returns a new GpsInjectData 7470 func NewGpsInjectData(TARGET_SYSTEM uint8, TARGET_COMPONENT uint8, LEN uint8, DATA [110]uint8) *GpsInjectData { 7471 m := GpsInjectData{} 7472 m.TARGET_SYSTEM = TARGET_SYSTEM 7473 m.TARGET_COMPONENT = TARGET_COMPONENT 7474 m.LEN = LEN 7475 m.DATA = DATA 7476 return &m 7477 } 7478 7479 // Id returns the GpsInjectData Message ID 7480 func (*GpsInjectData) Id() uint8 { 7481 return 123 7482 } 7483 7484 // Len returns the GpsInjectData Message Length 7485 func (*GpsInjectData) Len() uint8 { 7486 return 113 7487 } 7488 7489 // Crc returns the GpsInjectData Message CRC 7490 func (*GpsInjectData) Crc() uint8 { 7491 return 250 7492 } 7493 7494 // Pack returns a packed byte array which represents a GpsInjectData payload 7495 func (m *GpsInjectData) Pack() []byte { 7496 data := new(bytes.Buffer) 7497 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 7498 binary.Write(data, binary.LittleEndian, m.TARGET_COMPONENT) 7499 binary.Write(data, binary.LittleEndian, m.LEN) 7500 binary.Write(data, binary.LittleEndian, m.DATA) 7501 return data.Bytes() 7502 } 7503 7504 // Decode accepts a packed byte array and populates the fields of the GpsInjectData 7505 func (m *GpsInjectData) Decode(buf []byte) { 7506 data := bytes.NewBuffer(buf) 7507 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 7508 binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) 7509 binary.Read(data, binary.LittleEndian, &m.LEN) 7510 binary.Read(data, binary.LittleEndian, &m.DATA) 7511 } 7512 7513 const ( 7514 MAVLINK_MSG_GPS_INJECT_DATA_FIELD_data_LEN = 110 7515 ) 7516 7517 // 7518 // MESSAGE GPS2_RAW 7519 // 7520 // MAVLINK_MSG_ID_GPS2_RAW 124 7521 // 7522 // MAVLINK_MSG_ID_GPS2_RAW_LEN 35 7523 // 7524 // MAVLINK_MSG_ID_GPS2_RAW_CRC 87 7525 // 7526 // 7527 type Gps2Raw struct { 7528 TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) 7529 LAT int32 // Latitude (WGS84), in degrees * 1E7 7530 LON int32 // Longitude (WGS84), in degrees * 1E7 7531 ALT int32 // Altitude (WGS84), in meters * 1000 (positive for up) 7532 DGPS_AGE uint32 // Age of DGPS info 7533 EPH uint16 // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX 7534 EPV uint16 // GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX 7535 VEL uint16 // GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX 7536 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 7537 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. 7538 SATELLITES_VISIBLE uint8 // Number of satellites visible. If unknown, set to 255 7539 DGPS_NUMCH uint8 // Number of DGPS satellites 7540 } 7541 7542 // NewGps2Raw returns a new Gps2Raw 7543 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 { 7544 m := Gps2Raw{} 7545 m.TIME_USEC = TIME_USEC 7546 m.LAT = LAT 7547 m.LON = LON 7548 m.ALT = ALT 7549 m.DGPS_AGE = DGPS_AGE 7550 m.EPH = EPH 7551 m.EPV = EPV 7552 m.VEL = VEL 7553 m.COG = COG 7554 m.FIX_TYPE = FIX_TYPE 7555 m.SATELLITES_VISIBLE = SATELLITES_VISIBLE 7556 m.DGPS_NUMCH = DGPS_NUMCH 7557 return &m 7558 } 7559 7560 // Id returns the Gps2Raw Message ID 7561 func (*Gps2Raw) Id() uint8 { 7562 return 124 7563 } 7564 7565 // Len returns the Gps2Raw Message Length 7566 func (*Gps2Raw) Len() uint8 { 7567 return 35 7568 } 7569 7570 // Crc returns the Gps2Raw Message CRC 7571 func (*Gps2Raw) Crc() uint8 { 7572 return 87 7573 } 7574 7575 // Pack returns a packed byte array which represents a Gps2Raw payload 7576 func (m *Gps2Raw) Pack() []byte { 7577 data := new(bytes.Buffer) 7578 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 7579 binary.Write(data, binary.LittleEndian, m.LAT) 7580 binary.Write(data, binary.LittleEndian, m.LON) 7581 binary.Write(data, binary.LittleEndian, m.ALT) 7582 binary.Write(data, binary.LittleEndian, m.DGPS_AGE) 7583 binary.Write(data, binary.LittleEndian, m.EPH) 7584 binary.Write(data, binary.LittleEndian, m.EPV) 7585 binary.Write(data, binary.LittleEndian, m.VEL) 7586 binary.Write(data, binary.LittleEndian, m.COG) 7587 binary.Write(data, binary.LittleEndian, m.FIX_TYPE) 7588 binary.Write(data, binary.LittleEndian, m.SATELLITES_VISIBLE) 7589 binary.Write(data, binary.LittleEndian, m.DGPS_NUMCH) 7590 return data.Bytes() 7591 } 7592 7593 // Decode accepts a packed byte array and populates the fields of the Gps2Raw 7594 func (m *Gps2Raw) Decode(buf []byte) { 7595 data := bytes.NewBuffer(buf) 7596 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 7597 binary.Read(data, binary.LittleEndian, &m.LAT) 7598 binary.Read(data, binary.LittleEndian, &m.LON) 7599 binary.Read(data, binary.LittleEndian, &m.ALT) 7600 binary.Read(data, binary.LittleEndian, &m.DGPS_AGE) 7601 binary.Read(data, binary.LittleEndian, &m.EPH) 7602 binary.Read(data, binary.LittleEndian, &m.EPV) 7603 binary.Read(data, binary.LittleEndian, &m.VEL) 7604 binary.Read(data, binary.LittleEndian, &m.COG) 7605 binary.Read(data, binary.LittleEndian, &m.FIX_TYPE) 7606 binary.Read(data, binary.LittleEndian, &m.SATELLITES_VISIBLE) 7607 binary.Read(data, binary.LittleEndian, &m.DGPS_NUMCH) 7608 } 7609 7610 // 7611 // MESSAGE POWER_STATUS 7612 // 7613 // MAVLINK_MSG_ID_POWER_STATUS 125 7614 // 7615 // MAVLINK_MSG_ID_POWER_STATUS_LEN 6 7616 // 7617 // MAVLINK_MSG_ID_POWER_STATUS_CRC 203 7618 // 7619 // 7620 type PowerStatus struct { 7621 VCC uint16 // 5V rail voltage in millivolts 7622 VSERVO uint16 // servo rail voltage in millivolts 7623 FLAGS uint16 // power supply status flags (see MAV_POWER_STATUS enum) 7624 } 7625 7626 // NewPowerStatus returns a new PowerStatus 7627 func NewPowerStatus(VCC uint16, VSERVO uint16, FLAGS uint16) *PowerStatus { 7628 m := PowerStatus{} 7629 m.VCC = VCC 7630 m.VSERVO = VSERVO 7631 m.FLAGS = FLAGS 7632 return &m 7633 } 7634 7635 // Id returns the PowerStatus Message ID 7636 func (*PowerStatus) Id() uint8 { 7637 return 125 7638 } 7639 7640 // Len returns the PowerStatus Message Length 7641 func (*PowerStatus) Len() uint8 { 7642 return 6 7643 } 7644 7645 // Crc returns the PowerStatus Message CRC 7646 func (*PowerStatus) Crc() uint8 { 7647 return 203 7648 } 7649 7650 // Pack returns a packed byte array which represents a PowerStatus payload 7651 func (m *PowerStatus) Pack() []byte { 7652 data := new(bytes.Buffer) 7653 binary.Write(data, binary.LittleEndian, m.VCC) 7654 binary.Write(data, binary.LittleEndian, m.VSERVO) 7655 binary.Write(data, binary.LittleEndian, m.FLAGS) 7656 return data.Bytes() 7657 } 7658 7659 // Decode accepts a packed byte array and populates the fields of the PowerStatus 7660 func (m *PowerStatus) Decode(buf []byte) { 7661 data := bytes.NewBuffer(buf) 7662 binary.Read(data, binary.LittleEndian, &m.VCC) 7663 binary.Read(data, binary.LittleEndian, &m.VSERVO) 7664 binary.Read(data, binary.LittleEndian, &m.FLAGS) 7665 } 7666 7667 // 7668 // MESSAGE SERIAL_CONTROL 7669 // 7670 // MAVLINK_MSG_ID_SERIAL_CONTROL 126 7671 // 7672 // MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79 7673 // 7674 // MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220 7675 // 7676 // 7677 type SerialControl struct { 7678 BAUDRATE uint32 // Baudrate of transfer. Zero means no change. 7679 TIMEOUT uint16 // Timeout for reply data in milliseconds 7680 DEVICE uint8 // See SERIAL_CONTROL_DEV enum 7681 FLAGS uint8 // See SERIAL_CONTROL_FLAG enum 7682 COUNT uint8 // how many bytes in this transfer 7683 DATA [70]uint8 // serial data 7684 } 7685 7686 // NewSerialControl returns a new SerialControl 7687 func NewSerialControl(BAUDRATE uint32, TIMEOUT uint16, DEVICE uint8, FLAGS uint8, COUNT uint8, DATA [70]uint8) *SerialControl { 7688 m := SerialControl{} 7689 m.BAUDRATE = BAUDRATE 7690 m.TIMEOUT = TIMEOUT 7691 m.DEVICE = DEVICE 7692 m.FLAGS = FLAGS 7693 m.COUNT = COUNT 7694 m.DATA = DATA 7695 return &m 7696 } 7697 7698 // Id returns the SerialControl Message ID 7699 func (*SerialControl) Id() uint8 { 7700 return 126 7701 } 7702 7703 // Len returns the SerialControl Message Length 7704 func (*SerialControl) Len() uint8 { 7705 return 79 7706 } 7707 7708 // Crc returns the SerialControl Message CRC 7709 func (*SerialControl) Crc() uint8 { 7710 return 220 7711 } 7712 7713 // Pack returns a packed byte array which represents a SerialControl payload 7714 func (m *SerialControl) Pack() []byte { 7715 data := new(bytes.Buffer) 7716 binary.Write(data, binary.LittleEndian, m.BAUDRATE) 7717 binary.Write(data, binary.LittleEndian, m.TIMEOUT) 7718 binary.Write(data, binary.LittleEndian, m.DEVICE) 7719 binary.Write(data, binary.LittleEndian, m.FLAGS) 7720 binary.Write(data, binary.LittleEndian, m.COUNT) 7721 binary.Write(data, binary.LittleEndian, m.DATA) 7722 return data.Bytes() 7723 } 7724 7725 // Decode accepts a packed byte array and populates the fields of the SerialControl 7726 func (m *SerialControl) Decode(buf []byte) { 7727 data := bytes.NewBuffer(buf) 7728 binary.Read(data, binary.LittleEndian, &m.BAUDRATE) 7729 binary.Read(data, binary.LittleEndian, &m.TIMEOUT) 7730 binary.Read(data, binary.LittleEndian, &m.DEVICE) 7731 binary.Read(data, binary.LittleEndian, &m.FLAGS) 7732 binary.Read(data, binary.LittleEndian, &m.COUNT) 7733 binary.Read(data, binary.LittleEndian, &m.DATA) 7734 } 7735 7736 const ( 7737 MAVLINK_MSG_SERIAL_CONTROL_FIELD_data_LEN = 70 7738 ) 7739 7740 // 7741 // MESSAGE GPS_RTK 7742 // 7743 // MAVLINK_MSG_ID_GPS_RTK 127 7744 // 7745 // MAVLINK_MSG_ID_GPS_RTK_LEN 35 7746 // 7747 // MAVLINK_MSG_ID_GPS_RTK_CRC 25 7748 // 7749 // 7750 type GpsRtk struct { 7751 TIME_LAST_BASELINE_MS uint32 // Time since boot of last baseline message received in ms. 7752 TOW uint32 // GPS Time of Week of last baseline 7753 BASELINE_A_MM int32 // Current baseline in ECEF x or NED north component in mm. 7754 BASELINE_B_MM int32 // Current baseline in ECEF y or NED east component in mm. 7755 BASELINE_C_MM int32 // Current baseline in ECEF z or NED down component in mm. 7756 ACCURACY uint32 // Current estimate of baseline accuracy. 7757 IAR_NUM_HYPOTHESES int32 // Current number of integer ambiguity hypotheses. 7758 WN uint16 // GPS Week Number of last baseline 7759 RTK_RECEIVER_ID uint8 // Identification of connected RTK receiver. 7760 RTK_HEALTH uint8 // GPS-specific health report for RTK data. 7761 RTK_RATE uint8 // Rate of baseline messages being received by GPS, in HZ 7762 NSATS uint8 // Current number of sats used for RTK calculation. 7763 BASELINE_COORDS_TYPE uint8 // Coordinate system of baseline. 0 == ECEF, 1 == NED 7764 } 7765 7766 // NewGpsRtk returns a new GpsRtk 7767 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 { 7768 m := GpsRtk{} 7769 m.TIME_LAST_BASELINE_MS = TIME_LAST_BASELINE_MS 7770 m.TOW = TOW 7771 m.BASELINE_A_MM = BASELINE_A_MM 7772 m.BASELINE_B_MM = BASELINE_B_MM 7773 m.BASELINE_C_MM = BASELINE_C_MM 7774 m.ACCURACY = ACCURACY 7775 m.IAR_NUM_HYPOTHESES = IAR_NUM_HYPOTHESES 7776 m.WN = WN 7777 m.RTK_RECEIVER_ID = RTK_RECEIVER_ID 7778 m.RTK_HEALTH = RTK_HEALTH 7779 m.RTK_RATE = RTK_RATE 7780 m.NSATS = NSATS 7781 m.BASELINE_COORDS_TYPE = BASELINE_COORDS_TYPE 7782 return &m 7783 } 7784 7785 // Id returns the GpsRtk Message ID 7786 func (*GpsRtk) Id() uint8 { 7787 return 127 7788 } 7789 7790 // Len returns the GpsRtk Message Length 7791 func (*GpsRtk) Len() uint8 { 7792 return 35 7793 } 7794 7795 // Crc returns the GpsRtk Message CRC 7796 func (*GpsRtk) Crc() uint8 { 7797 return 25 7798 } 7799 7800 // Pack returns a packed byte array which represents a GpsRtk payload 7801 func (m *GpsRtk) Pack() []byte { 7802 data := new(bytes.Buffer) 7803 binary.Write(data, binary.LittleEndian, m.TIME_LAST_BASELINE_MS) 7804 binary.Write(data, binary.LittleEndian, m.TOW) 7805 binary.Write(data, binary.LittleEndian, m.BASELINE_A_MM) 7806 binary.Write(data, binary.LittleEndian, m.BASELINE_B_MM) 7807 binary.Write(data, binary.LittleEndian, m.BASELINE_C_MM) 7808 binary.Write(data, binary.LittleEndian, m.ACCURACY) 7809 binary.Write(data, binary.LittleEndian, m.IAR_NUM_HYPOTHESES) 7810 binary.Write(data, binary.LittleEndian, m.WN) 7811 binary.Write(data, binary.LittleEndian, m.RTK_RECEIVER_ID) 7812 binary.Write(data, binary.LittleEndian, m.RTK_HEALTH) 7813 binary.Write(data, binary.LittleEndian, m.RTK_RATE) 7814 binary.Write(data, binary.LittleEndian, m.NSATS) 7815 binary.Write(data, binary.LittleEndian, m.BASELINE_COORDS_TYPE) 7816 return data.Bytes() 7817 } 7818 7819 // Decode accepts a packed byte array and populates the fields of the GpsRtk 7820 func (m *GpsRtk) Decode(buf []byte) { 7821 data := bytes.NewBuffer(buf) 7822 binary.Read(data, binary.LittleEndian, &m.TIME_LAST_BASELINE_MS) 7823 binary.Read(data, binary.LittleEndian, &m.TOW) 7824 binary.Read(data, binary.LittleEndian, &m.BASELINE_A_MM) 7825 binary.Read(data, binary.LittleEndian, &m.BASELINE_B_MM) 7826 binary.Read(data, binary.LittleEndian, &m.BASELINE_C_MM) 7827 binary.Read(data, binary.LittleEndian, &m.ACCURACY) 7828 binary.Read(data, binary.LittleEndian, &m.IAR_NUM_HYPOTHESES) 7829 binary.Read(data, binary.LittleEndian, &m.WN) 7830 binary.Read(data, binary.LittleEndian, &m.RTK_RECEIVER_ID) 7831 binary.Read(data, binary.LittleEndian, &m.RTK_HEALTH) 7832 binary.Read(data, binary.LittleEndian, &m.RTK_RATE) 7833 binary.Read(data, binary.LittleEndian, &m.NSATS) 7834 binary.Read(data, binary.LittleEndian, &m.BASELINE_COORDS_TYPE) 7835 } 7836 7837 // 7838 // MESSAGE GPS2_RTK 7839 // 7840 // MAVLINK_MSG_ID_GPS2_RTK 128 7841 // 7842 // MAVLINK_MSG_ID_GPS2_RTK_LEN 35 7843 // 7844 // MAVLINK_MSG_ID_GPS2_RTK_CRC 226 7845 // 7846 // 7847 type Gps2Rtk struct { 7848 TIME_LAST_BASELINE_MS uint32 // Time since boot of last baseline message received in ms. 7849 TOW uint32 // GPS Time of Week of last baseline 7850 BASELINE_A_MM int32 // Current baseline in ECEF x or NED north component in mm. 7851 BASELINE_B_MM int32 // Current baseline in ECEF y or NED east component in mm. 7852 BASELINE_C_MM int32 // Current baseline in ECEF z or NED down component in mm. 7853 ACCURACY uint32 // Current estimate of baseline accuracy. 7854 IAR_NUM_HYPOTHESES int32 // Current number of integer ambiguity hypotheses. 7855 WN uint16 // GPS Week Number of last baseline 7856 RTK_RECEIVER_ID uint8 // Identification of connected RTK receiver. 7857 RTK_HEALTH uint8 // GPS-specific health report for RTK data. 7858 RTK_RATE uint8 // Rate of baseline messages being received by GPS, in HZ 7859 NSATS uint8 // Current number of sats used for RTK calculation. 7860 BASELINE_COORDS_TYPE uint8 // Coordinate system of baseline. 0 == ECEF, 1 == NED 7861 } 7862 7863 // NewGps2Rtk returns a new Gps2Rtk 7864 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 { 7865 m := Gps2Rtk{} 7866 m.TIME_LAST_BASELINE_MS = TIME_LAST_BASELINE_MS 7867 m.TOW = TOW 7868 m.BASELINE_A_MM = BASELINE_A_MM 7869 m.BASELINE_B_MM = BASELINE_B_MM 7870 m.BASELINE_C_MM = BASELINE_C_MM 7871 m.ACCURACY = ACCURACY 7872 m.IAR_NUM_HYPOTHESES = IAR_NUM_HYPOTHESES 7873 m.WN = WN 7874 m.RTK_RECEIVER_ID = RTK_RECEIVER_ID 7875 m.RTK_HEALTH = RTK_HEALTH 7876 m.RTK_RATE = RTK_RATE 7877 m.NSATS = NSATS 7878 m.BASELINE_COORDS_TYPE = BASELINE_COORDS_TYPE 7879 return &m 7880 } 7881 7882 // Id returns the Gps2Rtk Message ID 7883 func (*Gps2Rtk) Id() uint8 { 7884 return 128 7885 } 7886 7887 // Len returns the Gps2Rtk Message Length 7888 func (*Gps2Rtk) Len() uint8 { 7889 return 35 7890 } 7891 7892 // Crc returns the Gps2Rtk Message CRC 7893 func (*Gps2Rtk) Crc() uint8 { 7894 return 226 7895 } 7896 7897 // Pack returns a packed byte array which represents a Gps2Rtk payload 7898 func (m *Gps2Rtk) Pack() []byte { 7899 data := new(bytes.Buffer) 7900 binary.Write(data, binary.LittleEndian, m.TIME_LAST_BASELINE_MS) 7901 binary.Write(data, binary.LittleEndian, m.TOW) 7902 binary.Write(data, binary.LittleEndian, m.BASELINE_A_MM) 7903 binary.Write(data, binary.LittleEndian, m.BASELINE_B_MM) 7904 binary.Write(data, binary.LittleEndian, m.BASELINE_C_MM) 7905 binary.Write(data, binary.LittleEndian, m.ACCURACY) 7906 binary.Write(data, binary.LittleEndian, m.IAR_NUM_HYPOTHESES) 7907 binary.Write(data, binary.LittleEndian, m.WN) 7908 binary.Write(data, binary.LittleEndian, m.RTK_RECEIVER_ID) 7909 binary.Write(data, binary.LittleEndian, m.RTK_HEALTH) 7910 binary.Write(data, binary.LittleEndian, m.RTK_RATE) 7911 binary.Write(data, binary.LittleEndian, m.NSATS) 7912 binary.Write(data, binary.LittleEndian, m.BASELINE_COORDS_TYPE) 7913 return data.Bytes() 7914 } 7915 7916 // Decode accepts a packed byte array and populates the fields of the Gps2Rtk 7917 func (m *Gps2Rtk) Decode(buf []byte) { 7918 data := bytes.NewBuffer(buf) 7919 binary.Read(data, binary.LittleEndian, &m.TIME_LAST_BASELINE_MS) 7920 binary.Read(data, binary.LittleEndian, &m.TOW) 7921 binary.Read(data, binary.LittleEndian, &m.BASELINE_A_MM) 7922 binary.Read(data, binary.LittleEndian, &m.BASELINE_B_MM) 7923 binary.Read(data, binary.LittleEndian, &m.BASELINE_C_MM) 7924 binary.Read(data, binary.LittleEndian, &m.ACCURACY) 7925 binary.Read(data, binary.LittleEndian, &m.IAR_NUM_HYPOTHESES) 7926 binary.Read(data, binary.LittleEndian, &m.WN) 7927 binary.Read(data, binary.LittleEndian, &m.RTK_RECEIVER_ID) 7928 binary.Read(data, binary.LittleEndian, &m.RTK_HEALTH) 7929 binary.Read(data, binary.LittleEndian, &m.RTK_RATE) 7930 binary.Read(data, binary.LittleEndian, &m.NSATS) 7931 binary.Read(data, binary.LittleEndian, &m.BASELINE_COORDS_TYPE) 7932 } 7933 7934 // 7935 // MESSAGE DATA_TRANSMISSION_HANDSHAKE 7936 // 7937 // MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130 7938 // 7939 // MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13 7940 // 7941 // MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29 7942 // 7943 // 7944 type DataTransmissionHandshake struct { 7945 SIZE uint32 // total data size in bytes (set on ACK only) 7946 WIDTH uint16 // Width of a matrix or image 7947 HEIGHT uint16 // Height of a matrix or image 7948 PACKETS uint16 // number of packets being sent (set on ACK only) 7949 TYPE uint8 // type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) 7950 PAYLOAD uint8 // payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) 7951 JPG_QUALITY uint8 // JPEG quality out of [1,100] 7952 } 7953 7954 // NewDataTransmissionHandshake returns a new DataTransmissionHandshake 7955 func NewDataTransmissionHandshake(SIZE uint32, WIDTH uint16, HEIGHT uint16, PACKETS uint16, TYPE uint8, PAYLOAD uint8, JPG_QUALITY uint8) *DataTransmissionHandshake { 7956 m := DataTransmissionHandshake{} 7957 m.SIZE = SIZE 7958 m.WIDTH = WIDTH 7959 m.HEIGHT = HEIGHT 7960 m.PACKETS = PACKETS 7961 m.TYPE = TYPE 7962 m.PAYLOAD = PAYLOAD 7963 m.JPG_QUALITY = JPG_QUALITY 7964 return &m 7965 } 7966 7967 // Id returns the DataTransmissionHandshake Message ID 7968 func (*DataTransmissionHandshake) Id() uint8 { 7969 return 130 7970 } 7971 7972 // Len returns the DataTransmissionHandshake Message Length 7973 func (*DataTransmissionHandshake) Len() uint8 { 7974 return 13 7975 } 7976 7977 // Crc returns the DataTransmissionHandshake Message CRC 7978 func (*DataTransmissionHandshake) Crc() uint8 { 7979 return 29 7980 } 7981 7982 // Pack returns a packed byte array which represents a DataTransmissionHandshake payload 7983 func (m *DataTransmissionHandshake) Pack() []byte { 7984 data := new(bytes.Buffer) 7985 binary.Write(data, binary.LittleEndian, m.SIZE) 7986 binary.Write(data, binary.LittleEndian, m.WIDTH) 7987 binary.Write(data, binary.LittleEndian, m.HEIGHT) 7988 binary.Write(data, binary.LittleEndian, m.PACKETS) 7989 binary.Write(data, binary.LittleEndian, m.TYPE) 7990 binary.Write(data, binary.LittleEndian, m.PAYLOAD) 7991 binary.Write(data, binary.LittleEndian, m.JPG_QUALITY) 7992 return data.Bytes() 7993 } 7994 7995 // Decode accepts a packed byte array and populates the fields of the DataTransmissionHandshake 7996 func (m *DataTransmissionHandshake) Decode(buf []byte) { 7997 data := bytes.NewBuffer(buf) 7998 binary.Read(data, binary.LittleEndian, &m.SIZE) 7999 binary.Read(data, binary.LittleEndian, &m.WIDTH) 8000 binary.Read(data, binary.LittleEndian, &m.HEIGHT) 8001 binary.Read(data, binary.LittleEndian, &m.PACKETS) 8002 binary.Read(data, binary.LittleEndian, &m.TYPE) 8003 binary.Read(data, binary.LittleEndian, &m.PAYLOAD) 8004 binary.Read(data, binary.LittleEndian, &m.JPG_QUALITY) 8005 } 8006 8007 // 8008 // MESSAGE ENCAPSULATED_DATA 8009 // 8010 // MAVLINK_MSG_ID_ENCAPSULATED_DATA 131 8011 // 8012 // MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255 8013 // 8014 // MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223 8015 // 8016 // 8017 type EncapsulatedData struct { 8018 SEQNR uint16 // sequence number (starting with 0 on every transmission) 8019 DATA [253]uint8 // image data bytes 8020 } 8021 8022 // NewEncapsulatedData returns a new EncapsulatedData 8023 func NewEncapsulatedData(SEQNR uint16, DATA [253]uint8) *EncapsulatedData { 8024 m := EncapsulatedData{} 8025 m.SEQNR = SEQNR 8026 m.DATA = DATA 8027 return &m 8028 } 8029 8030 // Id returns the EncapsulatedData Message ID 8031 func (*EncapsulatedData) Id() uint8 { 8032 return 131 8033 } 8034 8035 // Len returns the EncapsulatedData Message Length 8036 func (*EncapsulatedData) Len() uint8 { 8037 return 255 8038 } 8039 8040 // Crc returns the EncapsulatedData Message CRC 8041 func (*EncapsulatedData) Crc() uint8 { 8042 return 223 8043 } 8044 8045 // Pack returns a packed byte array which represents a EncapsulatedData payload 8046 func (m *EncapsulatedData) Pack() []byte { 8047 data := new(bytes.Buffer) 8048 binary.Write(data, binary.LittleEndian, m.SEQNR) 8049 binary.Write(data, binary.LittleEndian, m.DATA) 8050 return data.Bytes() 8051 } 8052 8053 // Decode accepts a packed byte array and populates the fields of the EncapsulatedData 8054 func (m *EncapsulatedData) Decode(buf []byte) { 8055 data := bytes.NewBuffer(buf) 8056 binary.Read(data, binary.LittleEndian, &m.SEQNR) 8057 binary.Read(data, binary.LittleEndian, &m.DATA) 8058 } 8059 8060 const ( 8061 MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_data_LEN = 253 8062 ) 8063 8064 // 8065 // MESSAGE DISTANCE_SENSOR 8066 // 8067 // MAVLINK_MSG_ID_DISTANCE_SENSOR 132 8068 // 8069 // MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14 8070 // 8071 // MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85 8072 // 8073 // 8074 type DistanceSensor struct { 8075 TIME_BOOT_MS uint32 // Time since system boot 8076 MIN_DISTANCE uint16 // Minimum distance the sensor can measure in centimeters 8077 MAX_DISTANCE uint16 // Maximum distance the sensor can measure in centimeters 8078 CURRENT_DISTANCE uint16 // Current distance reading 8079 TYPE uint8 // Type from MAV_DISTANCE_SENSOR enum. 8080 ID uint8 // Onboard ID of the sensor 8081 ORIENTATION uint8 // Direction the sensor faces from FIXME enum. 8082 COVARIANCE uint8 // Measurement covariance in centimeters, 0 for unknown / invalid readings 8083 } 8084 8085 // NewDistanceSensor returns a new DistanceSensor 8086 func NewDistanceSensor(TIME_BOOT_MS uint32, MIN_DISTANCE uint16, MAX_DISTANCE uint16, CURRENT_DISTANCE uint16, TYPE uint8, ID uint8, ORIENTATION uint8, COVARIANCE uint8) *DistanceSensor { 8087 m := DistanceSensor{} 8088 m.TIME_BOOT_MS = TIME_BOOT_MS 8089 m.MIN_DISTANCE = MIN_DISTANCE 8090 m.MAX_DISTANCE = MAX_DISTANCE 8091 m.CURRENT_DISTANCE = CURRENT_DISTANCE 8092 m.TYPE = TYPE 8093 m.ID = ID 8094 m.ORIENTATION = ORIENTATION 8095 m.COVARIANCE = COVARIANCE 8096 return &m 8097 } 8098 8099 // Id returns the DistanceSensor Message ID 8100 func (*DistanceSensor) Id() uint8 { 8101 return 132 8102 } 8103 8104 // Len returns the DistanceSensor Message Length 8105 func (*DistanceSensor) Len() uint8 { 8106 return 14 8107 } 8108 8109 // Crc returns the DistanceSensor Message CRC 8110 func (*DistanceSensor) Crc() uint8 { 8111 return 85 8112 } 8113 8114 // Pack returns a packed byte array which represents a DistanceSensor payload 8115 func (m *DistanceSensor) Pack() []byte { 8116 data := new(bytes.Buffer) 8117 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 8118 binary.Write(data, binary.LittleEndian, m.MIN_DISTANCE) 8119 binary.Write(data, binary.LittleEndian, m.MAX_DISTANCE) 8120 binary.Write(data, binary.LittleEndian, m.CURRENT_DISTANCE) 8121 binary.Write(data, binary.LittleEndian, m.TYPE) 8122 binary.Write(data, binary.LittleEndian, m.ID) 8123 binary.Write(data, binary.LittleEndian, m.ORIENTATION) 8124 binary.Write(data, binary.LittleEndian, m.COVARIANCE) 8125 return data.Bytes() 8126 } 8127 8128 // Decode accepts a packed byte array and populates the fields of the DistanceSensor 8129 func (m *DistanceSensor) Decode(buf []byte) { 8130 data := bytes.NewBuffer(buf) 8131 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 8132 binary.Read(data, binary.LittleEndian, &m.MIN_DISTANCE) 8133 binary.Read(data, binary.LittleEndian, &m.MAX_DISTANCE) 8134 binary.Read(data, binary.LittleEndian, &m.CURRENT_DISTANCE) 8135 binary.Read(data, binary.LittleEndian, &m.TYPE) 8136 binary.Read(data, binary.LittleEndian, &m.ID) 8137 binary.Read(data, binary.LittleEndian, &m.ORIENTATION) 8138 binary.Read(data, binary.LittleEndian, &m.COVARIANCE) 8139 } 8140 8141 // 8142 // MESSAGE TERRAIN_REQUEST 8143 // 8144 // MAVLINK_MSG_ID_TERRAIN_REQUEST 133 8145 // 8146 // MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18 8147 // 8148 // MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC 6 8149 // 8150 // 8151 type TerrainRequest struct { 8152 MASK uint64 // Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) 8153 LAT int32 // Latitude of SW corner of first grid (degrees *10^7) 8154 LON int32 // Longitude of SW corner of first grid (in degrees *10^7) 8155 GRID_SPACING uint16 // Grid spacing in meters 8156 } 8157 8158 // NewTerrainRequest returns a new TerrainRequest 8159 func NewTerrainRequest(MASK uint64, LAT int32, LON int32, GRID_SPACING uint16) *TerrainRequest { 8160 m := TerrainRequest{} 8161 m.MASK = MASK 8162 m.LAT = LAT 8163 m.LON = LON 8164 m.GRID_SPACING = GRID_SPACING 8165 return &m 8166 } 8167 8168 // Id returns the TerrainRequest Message ID 8169 func (*TerrainRequest) Id() uint8 { 8170 return 133 8171 } 8172 8173 // Len returns the TerrainRequest Message Length 8174 func (*TerrainRequest) Len() uint8 { 8175 return 18 8176 } 8177 8178 // Crc returns the TerrainRequest Message CRC 8179 func (*TerrainRequest) Crc() uint8 { 8180 return 6 8181 } 8182 8183 // Pack returns a packed byte array which represents a TerrainRequest payload 8184 func (m *TerrainRequest) Pack() []byte { 8185 data := new(bytes.Buffer) 8186 binary.Write(data, binary.LittleEndian, m.MASK) 8187 binary.Write(data, binary.LittleEndian, m.LAT) 8188 binary.Write(data, binary.LittleEndian, m.LON) 8189 binary.Write(data, binary.LittleEndian, m.GRID_SPACING) 8190 return data.Bytes() 8191 } 8192 8193 // Decode accepts a packed byte array and populates the fields of the TerrainRequest 8194 func (m *TerrainRequest) Decode(buf []byte) { 8195 data := bytes.NewBuffer(buf) 8196 binary.Read(data, binary.LittleEndian, &m.MASK) 8197 binary.Read(data, binary.LittleEndian, &m.LAT) 8198 binary.Read(data, binary.LittleEndian, &m.LON) 8199 binary.Read(data, binary.LittleEndian, &m.GRID_SPACING) 8200 } 8201 8202 // 8203 // MESSAGE TERRAIN_DATA 8204 // 8205 // MAVLINK_MSG_ID_TERRAIN_DATA 134 8206 // 8207 // MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43 8208 // 8209 // MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229 8210 // 8211 // 8212 type TerrainData struct { 8213 LAT int32 // Latitude of SW corner of first grid (degrees *10^7) 8214 LON int32 // Longitude of SW corner of first grid (in degrees *10^7) 8215 GRID_SPACING uint16 // Grid spacing in meters 8216 DATA [16]int16 // Terrain data in meters AMSL 8217 GRIDBIT uint8 // bit within the terrain request mask 8218 } 8219 8220 // NewTerrainData returns a new TerrainData 8221 func NewTerrainData(LAT int32, LON int32, GRID_SPACING uint16, DATA [16]int16, GRIDBIT uint8) *TerrainData { 8222 m := TerrainData{} 8223 m.LAT = LAT 8224 m.LON = LON 8225 m.GRID_SPACING = GRID_SPACING 8226 m.DATA = DATA 8227 m.GRIDBIT = GRIDBIT 8228 return &m 8229 } 8230 8231 // Id returns the TerrainData Message ID 8232 func (*TerrainData) Id() uint8 { 8233 return 134 8234 } 8235 8236 // Len returns the TerrainData Message Length 8237 func (*TerrainData) Len() uint8 { 8238 return 43 8239 } 8240 8241 // Crc returns the TerrainData Message CRC 8242 func (*TerrainData) Crc() uint8 { 8243 return 229 8244 } 8245 8246 // Pack returns a packed byte array which represents a TerrainData payload 8247 func (m *TerrainData) Pack() []byte { 8248 data := new(bytes.Buffer) 8249 binary.Write(data, binary.LittleEndian, m.LAT) 8250 binary.Write(data, binary.LittleEndian, m.LON) 8251 binary.Write(data, binary.LittleEndian, m.GRID_SPACING) 8252 binary.Write(data, binary.LittleEndian, m.DATA) 8253 binary.Write(data, binary.LittleEndian, m.GRIDBIT) 8254 return data.Bytes() 8255 } 8256 8257 // Decode accepts a packed byte array and populates the fields of the TerrainData 8258 func (m *TerrainData) Decode(buf []byte) { 8259 data := bytes.NewBuffer(buf) 8260 binary.Read(data, binary.LittleEndian, &m.LAT) 8261 binary.Read(data, binary.LittleEndian, &m.LON) 8262 binary.Read(data, binary.LittleEndian, &m.GRID_SPACING) 8263 binary.Read(data, binary.LittleEndian, &m.DATA) 8264 binary.Read(data, binary.LittleEndian, &m.GRIDBIT) 8265 } 8266 8267 const ( 8268 MAVLINK_MSG_TERRAIN_DATA_FIELD_data_LEN = 16 8269 ) 8270 8271 // 8272 // MESSAGE TERRAIN_CHECK 8273 // 8274 // MAVLINK_MSG_ID_TERRAIN_CHECK 135 8275 // 8276 // MAVLINK_MSG_ID_TERRAIN_CHECK_LEN 8 8277 // 8278 // MAVLINK_MSG_ID_TERRAIN_CHECK_CRC 203 8279 // 8280 // 8281 type TerrainCheck struct { 8282 LAT int32 // Latitude (degrees *10^7) 8283 LON int32 // Longitude (degrees *10^7) 8284 } 8285 8286 // NewTerrainCheck returns a new TerrainCheck 8287 func NewTerrainCheck(LAT int32, LON int32) *TerrainCheck { 8288 m := TerrainCheck{} 8289 m.LAT = LAT 8290 m.LON = LON 8291 return &m 8292 } 8293 8294 // Id returns the TerrainCheck Message ID 8295 func (*TerrainCheck) Id() uint8 { 8296 return 135 8297 } 8298 8299 // Len returns the TerrainCheck Message Length 8300 func (*TerrainCheck) Len() uint8 { 8301 return 8 8302 } 8303 8304 // Crc returns the TerrainCheck Message CRC 8305 func (*TerrainCheck) Crc() uint8 { 8306 return 203 8307 } 8308 8309 // Pack returns a packed byte array which represents a TerrainCheck payload 8310 func (m *TerrainCheck) Pack() []byte { 8311 data := new(bytes.Buffer) 8312 binary.Write(data, binary.LittleEndian, m.LAT) 8313 binary.Write(data, binary.LittleEndian, m.LON) 8314 return data.Bytes() 8315 } 8316 8317 // Decode accepts a packed byte array and populates the fields of the TerrainCheck 8318 func (m *TerrainCheck) Decode(buf []byte) { 8319 data := bytes.NewBuffer(buf) 8320 binary.Read(data, binary.LittleEndian, &m.LAT) 8321 binary.Read(data, binary.LittleEndian, &m.LON) 8322 } 8323 8324 // 8325 // MESSAGE TERRAIN_REPORT 8326 // 8327 // MAVLINK_MSG_ID_TERRAIN_REPORT 136 8328 // 8329 // MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22 8330 // 8331 // MAVLINK_MSG_ID_TERRAIN_REPORT_CRC 1 8332 // 8333 // 8334 type TerrainReport struct { 8335 LAT int32 // Latitude (degrees *10^7) 8336 LON int32 // Longitude (degrees *10^7) 8337 TERRAIN_HEIGHT float32 // Terrain height in meters AMSL 8338 CURRENT_HEIGHT float32 // Current vehicle height above lat/lon terrain height (meters) 8339 SPACING uint16 // grid spacing (zero if terrain at this location unavailable) 8340 PENDING uint16 // Number of 4x4 terrain blocks waiting to be received or read from disk 8341 LOADED uint16 // Number of 4x4 terrain blocks in memory 8342 } 8343 8344 // NewTerrainReport returns a new TerrainReport 8345 func NewTerrainReport(LAT int32, LON int32, TERRAIN_HEIGHT float32, CURRENT_HEIGHT float32, SPACING uint16, PENDING uint16, LOADED uint16) *TerrainReport { 8346 m := TerrainReport{} 8347 m.LAT = LAT 8348 m.LON = LON 8349 m.TERRAIN_HEIGHT = TERRAIN_HEIGHT 8350 m.CURRENT_HEIGHT = CURRENT_HEIGHT 8351 m.SPACING = SPACING 8352 m.PENDING = PENDING 8353 m.LOADED = LOADED 8354 return &m 8355 } 8356 8357 // Id returns the TerrainReport Message ID 8358 func (*TerrainReport) Id() uint8 { 8359 return 136 8360 } 8361 8362 // Len returns the TerrainReport Message Length 8363 func (*TerrainReport) Len() uint8 { 8364 return 22 8365 } 8366 8367 // Crc returns the TerrainReport Message CRC 8368 func (*TerrainReport) Crc() uint8 { 8369 return 1 8370 } 8371 8372 // Pack returns a packed byte array which represents a TerrainReport payload 8373 func (m *TerrainReport) Pack() []byte { 8374 data := new(bytes.Buffer) 8375 binary.Write(data, binary.LittleEndian, m.LAT) 8376 binary.Write(data, binary.LittleEndian, m.LON) 8377 binary.Write(data, binary.LittleEndian, m.TERRAIN_HEIGHT) 8378 binary.Write(data, binary.LittleEndian, m.CURRENT_HEIGHT) 8379 binary.Write(data, binary.LittleEndian, m.SPACING) 8380 binary.Write(data, binary.LittleEndian, m.PENDING) 8381 binary.Write(data, binary.LittleEndian, m.LOADED) 8382 return data.Bytes() 8383 } 8384 8385 // Decode accepts a packed byte array and populates the fields of the TerrainReport 8386 func (m *TerrainReport) Decode(buf []byte) { 8387 data := bytes.NewBuffer(buf) 8388 binary.Read(data, binary.LittleEndian, &m.LAT) 8389 binary.Read(data, binary.LittleEndian, &m.LON) 8390 binary.Read(data, binary.LittleEndian, &m.TERRAIN_HEIGHT) 8391 binary.Read(data, binary.LittleEndian, &m.CURRENT_HEIGHT) 8392 binary.Read(data, binary.LittleEndian, &m.SPACING) 8393 binary.Read(data, binary.LittleEndian, &m.PENDING) 8394 binary.Read(data, binary.LittleEndian, &m.LOADED) 8395 } 8396 8397 // 8398 // MESSAGE BATTERY_STATUS 8399 // 8400 // MAVLINK_MSG_ID_BATTERY_STATUS 147 8401 // 8402 // MAVLINK_MSG_ID_BATTERY_STATUS_LEN 24 8403 // 8404 // MAVLINK_MSG_ID_BATTERY_STATUS_CRC 177 8405 // 8406 // 8407 type BatteryStatus struct { 8408 CURRENT_CONSUMED int32 // Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate 8409 ENERGY_CONSUMED int32 // Consumed energy, in 100*Joules (integrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate 8410 VOLTAGE_CELL_1 uint16 // Battery voltage of cell 1, in millivolts (1 = 1 millivolt) 8411 VOLTAGE_CELL_2 uint16 // Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell 8412 VOLTAGE_CELL_3 uint16 // Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell 8413 VOLTAGE_CELL_4 uint16 // Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell 8414 VOLTAGE_CELL_5 uint16 // Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell 8415 VOLTAGE_CELL_6 uint16 // Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell 8416 CURRENT_BATTERY int16 // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current 8417 ACCU_ID uint8 // Accupack ID 8418 BATTERY_REMAINING int8 // Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery 8419 } 8420 8421 // NewBatteryStatus returns a new BatteryStatus 8422 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 { 8423 m := BatteryStatus{} 8424 m.CURRENT_CONSUMED = CURRENT_CONSUMED 8425 m.ENERGY_CONSUMED = ENERGY_CONSUMED 8426 m.VOLTAGE_CELL_1 = VOLTAGE_CELL_1 8427 m.VOLTAGE_CELL_2 = VOLTAGE_CELL_2 8428 m.VOLTAGE_CELL_3 = VOLTAGE_CELL_3 8429 m.VOLTAGE_CELL_4 = VOLTAGE_CELL_4 8430 m.VOLTAGE_CELL_5 = VOLTAGE_CELL_5 8431 m.VOLTAGE_CELL_6 = VOLTAGE_CELL_6 8432 m.CURRENT_BATTERY = CURRENT_BATTERY 8433 m.ACCU_ID = ACCU_ID 8434 m.BATTERY_REMAINING = BATTERY_REMAINING 8435 return &m 8436 } 8437 8438 // Id returns the BatteryStatus Message ID 8439 func (*BatteryStatus) Id() uint8 { 8440 return 147 8441 } 8442 8443 // Len returns the BatteryStatus Message Length 8444 func (*BatteryStatus) Len() uint8 { 8445 return 24 8446 } 8447 8448 // Crc returns the BatteryStatus Message CRC 8449 func (*BatteryStatus) Crc() uint8 { 8450 return 177 8451 } 8452 8453 // Pack returns a packed byte array which represents a BatteryStatus payload 8454 func (m *BatteryStatus) Pack() []byte { 8455 data := new(bytes.Buffer) 8456 binary.Write(data, binary.LittleEndian, m.CURRENT_CONSUMED) 8457 binary.Write(data, binary.LittleEndian, m.ENERGY_CONSUMED) 8458 binary.Write(data, binary.LittleEndian, m.VOLTAGE_CELL_1) 8459 binary.Write(data, binary.LittleEndian, m.VOLTAGE_CELL_2) 8460 binary.Write(data, binary.LittleEndian, m.VOLTAGE_CELL_3) 8461 binary.Write(data, binary.LittleEndian, m.VOLTAGE_CELL_4) 8462 binary.Write(data, binary.LittleEndian, m.VOLTAGE_CELL_5) 8463 binary.Write(data, binary.LittleEndian, m.VOLTAGE_CELL_6) 8464 binary.Write(data, binary.LittleEndian, m.CURRENT_BATTERY) 8465 binary.Write(data, binary.LittleEndian, m.ACCU_ID) 8466 binary.Write(data, binary.LittleEndian, m.BATTERY_REMAINING) 8467 return data.Bytes() 8468 } 8469 8470 // Decode accepts a packed byte array and populates the fields of the BatteryStatus 8471 func (m *BatteryStatus) Decode(buf []byte) { 8472 data := bytes.NewBuffer(buf) 8473 binary.Read(data, binary.LittleEndian, &m.CURRENT_CONSUMED) 8474 binary.Read(data, binary.LittleEndian, &m.ENERGY_CONSUMED) 8475 binary.Read(data, binary.LittleEndian, &m.VOLTAGE_CELL_1) 8476 binary.Read(data, binary.LittleEndian, &m.VOLTAGE_CELL_2) 8477 binary.Read(data, binary.LittleEndian, &m.VOLTAGE_CELL_3) 8478 binary.Read(data, binary.LittleEndian, &m.VOLTAGE_CELL_4) 8479 binary.Read(data, binary.LittleEndian, &m.VOLTAGE_CELL_5) 8480 binary.Read(data, binary.LittleEndian, &m.VOLTAGE_CELL_6) 8481 binary.Read(data, binary.LittleEndian, &m.CURRENT_BATTERY) 8482 binary.Read(data, binary.LittleEndian, &m.ACCU_ID) 8483 binary.Read(data, binary.LittleEndian, &m.BATTERY_REMAINING) 8484 } 8485 8486 // 8487 // MESSAGE SETPOINT_8DOF 8488 // 8489 // MAVLINK_MSG_ID_SETPOINT_8DOF 148 8490 // 8491 // MAVLINK_MSG_ID_SETPOINT_8DOF_LEN 33 8492 // 8493 // MAVLINK_MSG_ID_SETPOINT_8DOF_CRC 241 8494 // 8495 // 8496 type Setpoint8Dof struct { 8497 VAL1 float32 // Value 1 8498 VAL2 float32 // Value 2 8499 VAL3 float32 // Value 3 8500 VAL4 float32 // Value 4 8501 VAL5 float32 // Value 5 8502 VAL6 float32 // Value 6 8503 VAL7 float32 // Value 7 8504 VAL8 float32 // Value 8 8505 TARGET_SYSTEM uint8 // System ID 8506 } 8507 8508 // NewSetpoint8Dof returns a new Setpoint8Dof 8509 func NewSetpoint8Dof(VAL1 float32, VAL2 float32, VAL3 float32, VAL4 float32, VAL5 float32, VAL6 float32, VAL7 float32, VAL8 float32, TARGET_SYSTEM uint8) *Setpoint8Dof { 8510 m := Setpoint8Dof{} 8511 m.VAL1 = VAL1 8512 m.VAL2 = VAL2 8513 m.VAL3 = VAL3 8514 m.VAL4 = VAL4 8515 m.VAL5 = VAL5 8516 m.VAL6 = VAL6 8517 m.VAL7 = VAL7 8518 m.VAL8 = VAL8 8519 m.TARGET_SYSTEM = TARGET_SYSTEM 8520 return &m 8521 } 8522 8523 // Id returns the Setpoint8Dof Message ID 8524 func (*Setpoint8Dof) Id() uint8 { 8525 return 148 8526 } 8527 8528 // Len returns the Setpoint8Dof Message Length 8529 func (*Setpoint8Dof) Len() uint8 { 8530 return 33 8531 } 8532 8533 // Crc returns the Setpoint8Dof Message CRC 8534 func (*Setpoint8Dof) Crc() uint8 { 8535 return 241 8536 } 8537 8538 // Pack returns a packed byte array which represents a Setpoint8Dof payload 8539 func (m *Setpoint8Dof) Pack() []byte { 8540 data := new(bytes.Buffer) 8541 binary.Write(data, binary.LittleEndian, m.VAL1) 8542 binary.Write(data, binary.LittleEndian, m.VAL2) 8543 binary.Write(data, binary.LittleEndian, m.VAL3) 8544 binary.Write(data, binary.LittleEndian, m.VAL4) 8545 binary.Write(data, binary.LittleEndian, m.VAL5) 8546 binary.Write(data, binary.LittleEndian, m.VAL6) 8547 binary.Write(data, binary.LittleEndian, m.VAL7) 8548 binary.Write(data, binary.LittleEndian, m.VAL8) 8549 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 8550 return data.Bytes() 8551 } 8552 8553 // Decode accepts a packed byte array and populates the fields of the Setpoint8Dof 8554 func (m *Setpoint8Dof) Decode(buf []byte) { 8555 data := bytes.NewBuffer(buf) 8556 binary.Read(data, binary.LittleEndian, &m.VAL1) 8557 binary.Read(data, binary.LittleEndian, &m.VAL2) 8558 binary.Read(data, binary.LittleEndian, &m.VAL3) 8559 binary.Read(data, binary.LittleEndian, &m.VAL4) 8560 binary.Read(data, binary.LittleEndian, &m.VAL5) 8561 binary.Read(data, binary.LittleEndian, &m.VAL6) 8562 binary.Read(data, binary.LittleEndian, &m.VAL7) 8563 binary.Read(data, binary.LittleEndian, &m.VAL8) 8564 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 8565 } 8566 8567 // 8568 // MESSAGE SETPOINT_6DOF 8569 // 8570 // MAVLINK_MSG_ID_SETPOINT_6DOF 149 8571 // 8572 // MAVLINK_MSG_ID_SETPOINT_6DOF_LEN 25 8573 // 8574 // MAVLINK_MSG_ID_SETPOINT_6DOF_CRC 15 8575 // 8576 // 8577 type Setpoint6Dof struct { 8578 TRANS_X float32 // Translational Component in x 8579 TRANS_Y float32 // Translational Component in y 8580 TRANS_Z float32 // Translational Component in z 8581 ROT_X float32 // Rotational Component in x 8582 ROT_Y float32 // Rotational Component in y 8583 ROT_Z float32 // Rotational Component in z 8584 TARGET_SYSTEM uint8 // System ID 8585 } 8586 8587 // NewSetpoint6Dof returns a new Setpoint6Dof 8588 func NewSetpoint6Dof(TRANS_X float32, TRANS_Y float32, TRANS_Z float32, ROT_X float32, ROT_Y float32, ROT_Z float32, TARGET_SYSTEM uint8) *Setpoint6Dof { 8589 m := Setpoint6Dof{} 8590 m.TRANS_X = TRANS_X 8591 m.TRANS_Y = TRANS_Y 8592 m.TRANS_Z = TRANS_Z 8593 m.ROT_X = ROT_X 8594 m.ROT_Y = ROT_Y 8595 m.ROT_Z = ROT_Z 8596 m.TARGET_SYSTEM = TARGET_SYSTEM 8597 return &m 8598 } 8599 8600 // Id returns the Setpoint6Dof Message ID 8601 func (*Setpoint6Dof) Id() uint8 { 8602 return 149 8603 } 8604 8605 // Len returns the Setpoint6Dof Message Length 8606 func (*Setpoint6Dof) Len() uint8 { 8607 return 25 8608 } 8609 8610 // Crc returns the Setpoint6Dof Message CRC 8611 func (*Setpoint6Dof) Crc() uint8 { 8612 return 15 8613 } 8614 8615 // Pack returns a packed byte array which represents a Setpoint6Dof payload 8616 func (m *Setpoint6Dof) Pack() []byte { 8617 data := new(bytes.Buffer) 8618 binary.Write(data, binary.LittleEndian, m.TRANS_X) 8619 binary.Write(data, binary.LittleEndian, m.TRANS_Y) 8620 binary.Write(data, binary.LittleEndian, m.TRANS_Z) 8621 binary.Write(data, binary.LittleEndian, m.ROT_X) 8622 binary.Write(data, binary.LittleEndian, m.ROT_Y) 8623 binary.Write(data, binary.LittleEndian, m.ROT_Z) 8624 binary.Write(data, binary.LittleEndian, m.TARGET_SYSTEM) 8625 return data.Bytes() 8626 } 8627 8628 // Decode accepts a packed byte array and populates the fields of the Setpoint6Dof 8629 func (m *Setpoint6Dof) Decode(buf []byte) { 8630 data := bytes.NewBuffer(buf) 8631 binary.Read(data, binary.LittleEndian, &m.TRANS_X) 8632 binary.Read(data, binary.LittleEndian, &m.TRANS_Y) 8633 binary.Read(data, binary.LittleEndian, &m.TRANS_Z) 8634 binary.Read(data, binary.LittleEndian, &m.ROT_X) 8635 binary.Read(data, binary.LittleEndian, &m.ROT_Y) 8636 binary.Read(data, binary.LittleEndian, &m.ROT_Z) 8637 binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) 8638 } 8639 8640 // 8641 // MESSAGE MEMORY_VECT 8642 // 8643 // MAVLINK_MSG_ID_MEMORY_VECT 249 8644 // 8645 // MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 8646 // 8647 // MAVLINK_MSG_ID_MEMORY_VECT_CRC 204 8648 // 8649 // 8650 type MemoryVect struct { 8651 ADDRESS uint16 // Starting address of the debug variables 8652 VER uint8 // Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below 8653 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 8654 VALUE [32]int8 // Memory contents at specified address 8655 } 8656 8657 // NewMemoryVect returns a new MemoryVect 8658 func NewMemoryVect(ADDRESS uint16, VER uint8, TYPE uint8, VALUE [32]int8) *MemoryVect { 8659 m := MemoryVect{} 8660 m.ADDRESS = ADDRESS 8661 m.VER = VER 8662 m.TYPE = TYPE 8663 m.VALUE = VALUE 8664 return &m 8665 } 8666 8667 // Id returns the MemoryVect Message ID 8668 func (*MemoryVect) Id() uint8 { 8669 return 249 8670 } 8671 8672 // Len returns the MemoryVect Message Length 8673 func (*MemoryVect) Len() uint8 { 8674 return 36 8675 } 8676 8677 // Crc returns the MemoryVect Message CRC 8678 func (*MemoryVect) Crc() uint8 { 8679 return 204 8680 } 8681 8682 // Pack returns a packed byte array which represents a MemoryVect payload 8683 func (m *MemoryVect) Pack() []byte { 8684 data := new(bytes.Buffer) 8685 binary.Write(data, binary.LittleEndian, m.ADDRESS) 8686 binary.Write(data, binary.LittleEndian, m.VER) 8687 binary.Write(data, binary.LittleEndian, m.TYPE) 8688 binary.Write(data, binary.LittleEndian, m.VALUE) 8689 return data.Bytes() 8690 } 8691 8692 // Decode accepts a packed byte array and populates the fields of the MemoryVect 8693 func (m *MemoryVect) Decode(buf []byte) { 8694 data := bytes.NewBuffer(buf) 8695 binary.Read(data, binary.LittleEndian, &m.ADDRESS) 8696 binary.Read(data, binary.LittleEndian, &m.VER) 8697 binary.Read(data, binary.LittleEndian, &m.TYPE) 8698 binary.Read(data, binary.LittleEndian, &m.VALUE) 8699 } 8700 8701 const ( 8702 MAVLINK_MSG_MEMORY_VECT_FIELD_value_LEN = 32 8703 ) 8704 8705 // 8706 // MESSAGE DEBUG_VECT 8707 // 8708 // MAVLINK_MSG_ID_DEBUG_VECT 250 8709 // 8710 // MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 8711 // 8712 // MAVLINK_MSG_ID_DEBUG_VECT_CRC 49 8713 // 8714 // 8715 type DebugVect struct { 8716 TIME_USEC uint64 // Timestamp 8717 X float32 // x 8718 Y float32 // y 8719 Z float32 // z 8720 NAME [10]uint8 // Name 8721 } 8722 8723 // NewDebugVect returns a new DebugVect 8724 func NewDebugVect(TIME_USEC uint64, X float32, Y float32, Z float32, NAME [10]uint8) *DebugVect { 8725 m := DebugVect{} 8726 m.TIME_USEC = TIME_USEC 8727 m.X = X 8728 m.Y = Y 8729 m.Z = Z 8730 m.NAME = NAME 8731 return &m 8732 } 8733 8734 // Id returns the DebugVect Message ID 8735 func (*DebugVect) Id() uint8 { 8736 return 250 8737 } 8738 8739 // Len returns the DebugVect Message Length 8740 func (*DebugVect) Len() uint8 { 8741 return 30 8742 } 8743 8744 // Crc returns the DebugVect Message CRC 8745 func (*DebugVect) Crc() uint8 { 8746 return 49 8747 } 8748 8749 // Pack returns a packed byte array which represents a DebugVect payload 8750 func (m *DebugVect) Pack() []byte { 8751 data := new(bytes.Buffer) 8752 binary.Write(data, binary.LittleEndian, m.TIME_USEC) 8753 binary.Write(data, binary.LittleEndian, m.X) 8754 binary.Write(data, binary.LittleEndian, m.Y) 8755 binary.Write(data, binary.LittleEndian, m.Z) 8756 binary.Write(data, binary.LittleEndian, m.NAME) 8757 return data.Bytes() 8758 } 8759 8760 // Decode accepts a packed byte array and populates the fields of the DebugVect 8761 func (m *DebugVect) Decode(buf []byte) { 8762 data := bytes.NewBuffer(buf) 8763 binary.Read(data, binary.LittleEndian, &m.TIME_USEC) 8764 binary.Read(data, binary.LittleEndian, &m.X) 8765 binary.Read(data, binary.LittleEndian, &m.Y) 8766 binary.Read(data, binary.LittleEndian, &m.Z) 8767 binary.Read(data, binary.LittleEndian, &m.NAME) 8768 } 8769 8770 const ( 8771 MAVLINK_MSG_DEBUG_VECT_FIELD_name_LEN = 10 8772 ) 8773 8774 // 8775 // MESSAGE NAMED_VALUE_FLOAT 8776 // 8777 // MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 8778 // 8779 // MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 8780 // 8781 // MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC 170 8782 // 8783 // 8784 type NamedValueFloat struct { 8785 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 8786 VALUE float32 // Floating point value 8787 NAME [10]uint8 // Name of the debug variable 8788 } 8789 8790 // NewNamedValueFloat returns a new NamedValueFloat 8791 func NewNamedValueFloat(TIME_BOOT_MS uint32, VALUE float32, NAME [10]uint8) *NamedValueFloat { 8792 m := NamedValueFloat{} 8793 m.TIME_BOOT_MS = TIME_BOOT_MS 8794 m.VALUE = VALUE 8795 m.NAME = NAME 8796 return &m 8797 } 8798 8799 // Id returns the NamedValueFloat Message ID 8800 func (*NamedValueFloat) Id() uint8 { 8801 return 251 8802 } 8803 8804 // Len returns the NamedValueFloat Message Length 8805 func (*NamedValueFloat) Len() uint8 { 8806 return 18 8807 } 8808 8809 // Crc returns the NamedValueFloat Message CRC 8810 func (*NamedValueFloat) Crc() uint8 { 8811 return 170 8812 } 8813 8814 // Pack returns a packed byte array which represents a NamedValueFloat payload 8815 func (m *NamedValueFloat) Pack() []byte { 8816 data := new(bytes.Buffer) 8817 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 8818 binary.Write(data, binary.LittleEndian, m.VALUE) 8819 binary.Write(data, binary.LittleEndian, m.NAME) 8820 return data.Bytes() 8821 } 8822 8823 // Decode accepts a packed byte array and populates the fields of the NamedValueFloat 8824 func (m *NamedValueFloat) Decode(buf []byte) { 8825 data := bytes.NewBuffer(buf) 8826 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 8827 binary.Read(data, binary.LittleEndian, &m.VALUE) 8828 binary.Read(data, binary.LittleEndian, &m.NAME) 8829 } 8830 8831 const ( 8832 MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_name_LEN = 10 8833 ) 8834 8835 // 8836 // MESSAGE NAMED_VALUE_INT 8837 // 8838 // MAVLINK_MSG_ID_NAMED_VALUE_INT 252 8839 // 8840 // MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 8841 // 8842 // MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC 44 8843 // 8844 // 8845 type NamedValueInt struct { 8846 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 8847 VALUE int32 // Signed integer value 8848 NAME [10]uint8 // Name of the debug variable 8849 } 8850 8851 // NewNamedValueInt returns a new NamedValueInt 8852 func NewNamedValueInt(TIME_BOOT_MS uint32, VALUE int32, NAME [10]uint8) *NamedValueInt { 8853 m := NamedValueInt{} 8854 m.TIME_BOOT_MS = TIME_BOOT_MS 8855 m.VALUE = VALUE 8856 m.NAME = NAME 8857 return &m 8858 } 8859 8860 // Id returns the NamedValueInt Message ID 8861 func (*NamedValueInt) Id() uint8 { 8862 return 252 8863 } 8864 8865 // Len returns the NamedValueInt Message Length 8866 func (*NamedValueInt) Len() uint8 { 8867 return 18 8868 } 8869 8870 // Crc returns the NamedValueInt Message CRC 8871 func (*NamedValueInt) Crc() uint8 { 8872 return 44 8873 } 8874 8875 // Pack returns a packed byte array which represents a NamedValueInt payload 8876 func (m *NamedValueInt) Pack() []byte { 8877 data := new(bytes.Buffer) 8878 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 8879 binary.Write(data, binary.LittleEndian, m.VALUE) 8880 binary.Write(data, binary.LittleEndian, m.NAME) 8881 return data.Bytes() 8882 } 8883 8884 // Decode accepts a packed byte array and populates the fields of the NamedValueInt 8885 func (m *NamedValueInt) Decode(buf []byte) { 8886 data := bytes.NewBuffer(buf) 8887 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 8888 binary.Read(data, binary.LittleEndian, &m.VALUE) 8889 binary.Read(data, binary.LittleEndian, &m.NAME) 8890 } 8891 8892 const ( 8893 MAVLINK_MSG_NAMED_VALUE_INT_FIELD_name_LEN = 10 8894 ) 8895 8896 // 8897 // MESSAGE STATUSTEXT 8898 // 8899 // MAVLINK_MSG_ID_STATUSTEXT 253 8900 // 8901 // MAVLINK_MSG_ID_STATUSTEXT_LEN 51 8902 // 8903 // MAVLINK_MSG_ID_STATUSTEXT_CRC 83 8904 // 8905 // 8906 type Statustext struct { 8907 SEVERITY uint8 // Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. 8908 TEXT [50]uint8 // Status text message, without null termination character 8909 } 8910 8911 // NewStatustext returns a new Statustext 8912 func NewStatustext(SEVERITY uint8, TEXT [50]uint8) *Statustext { 8913 m := Statustext{} 8914 m.SEVERITY = SEVERITY 8915 m.TEXT = TEXT 8916 return &m 8917 } 8918 8919 // Id returns the Statustext Message ID 8920 func (*Statustext) Id() uint8 { 8921 return 253 8922 } 8923 8924 // Len returns the Statustext Message Length 8925 func (*Statustext) Len() uint8 { 8926 return 51 8927 } 8928 8929 // Crc returns the Statustext Message CRC 8930 func (*Statustext) Crc() uint8 { 8931 return 83 8932 } 8933 8934 // Pack returns a packed byte array which represents a Statustext payload 8935 func (m *Statustext) Pack() []byte { 8936 data := new(bytes.Buffer) 8937 binary.Write(data, binary.LittleEndian, m.SEVERITY) 8938 binary.Write(data, binary.LittleEndian, m.TEXT) 8939 return data.Bytes() 8940 } 8941 8942 // Decode accepts a packed byte array and populates the fields of the Statustext 8943 func (m *Statustext) Decode(buf []byte) { 8944 data := bytes.NewBuffer(buf) 8945 binary.Read(data, binary.LittleEndian, &m.SEVERITY) 8946 binary.Read(data, binary.LittleEndian, &m.TEXT) 8947 } 8948 8949 const ( 8950 MAVLINK_MSG_STATUSTEXT_FIELD_text_LEN = 50 8951 ) 8952 8953 // 8954 // MESSAGE DEBUG 8955 // 8956 // MAVLINK_MSG_ID_DEBUG 254 8957 // 8958 // MAVLINK_MSG_ID_DEBUG_LEN 9 8959 // 8960 // MAVLINK_MSG_ID_DEBUG_CRC 46 8961 // 8962 // 8963 type Debug struct { 8964 TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) 8965 VALUE float32 // DEBUG value 8966 IND uint8 // index of debug variable 8967 } 8968 8969 // NewDebug returns a new Debug 8970 func NewDebug(TIME_BOOT_MS uint32, VALUE float32, IND uint8) *Debug { 8971 m := Debug{} 8972 m.TIME_BOOT_MS = TIME_BOOT_MS 8973 m.VALUE = VALUE 8974 m.IND = IND 8975 return &m 8976 } 8977 8978 // Id returns the Debug Message ID 8979 func (*Debug) Id() uint8 { 8980 return 254 8981 } 8982 8983 // Len returns the Debug Message Length 8984 func (*Debug) Len() uint8 { 8985 return 9 8986 } 8987 8988 // Crc returns the Debug Message CRC 8989 func (*Debug) Crc() uint8 { 8990 return 46 8991 } 8992 8993 // Pack returns a packed byte array which represents a Debug payload 8994 func (m *Debug) Pack() []byte { 8995 data := new(bytes.Buffer) 8996 binary.Write(data, binary.LittleEndian, m.TIME_BOOT_MS) 8997 binary.Write(data, binary.LittleEndian, m.VALUE) 8998 binary.Write(data, binary.LittleEndian, m.IND) 8999 return data.Bytes() 9000 } 9001 9002 // Decode accepts a packed byte array and populates the fields of the Debug 9003 func (m *Debug) Decode(buf []byte) { 9004 data := bytes.NewBuffer(buf) 9005 binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) 9006 binary.Read(data, binary.LittleEndian, &m.VALUE) 9007 binary.Read(data, binary.LittleEndian, &m.IND) 9008 }