slugs

package
v0.0.0-...-4f9df97 Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: Feb 11, 2016 License: MIT Imports: 3 Imported by: 0

Documentation

Index

Constants

View Source
const (
	PROTOCOL_NAME = "slugs"

	PROTOCOL_INCLUDE = common.PROTOCOL_NAME
)
View Source
const (
	MAV_CMD_DO_NOTHING             = 0 // Does nothing.
	MAV_CMD_RETURN_TO_BASE         = 0 // Return vehicle to base.
	MAV_CMD_STOP_RETURN_TO_BASE    = 0 // Stops the vehicle from returning to base and resumes flight.
	MAV_CMD_TURN_LIGHT             = 0 // Turns the vehicle's visible or infrared lights on or off.
	MAV_CMD_GET_MID_LEVEL_COMMANDS = 0 // Requests vehicle to send current mid-level commands to ground station.
	MAV_CMD_MIDLEVEL_STORAGE       = 0 // Requests storage of mid-level commands.
)

MAV_CMD:

View Source
const (
	SLUGS_MODE_NONE                  = 0  // No change to SLUGS mode.
	SLUGS_MODE_LIFTOFF               = 1  // Vehicle is in liftoff mode.
	SLUGS_MODE_PASSTHROUGH           = 2  // Vehicle is in passthrough mode, being controlled by a pilot.
	SLUGS_MODE_WAYPOINT              = 3  // Vehicle is in waypoint mode, navigating to waypoints.
	SLUGS_MODE_MID_LEVEL             = 4  // Vehicle is executing mid-level commands.
	SLUGS_MODE_RETURNING             = 5  // Vehicle is returning to the home location.
	SLUGS_MODE_LANDING               = 6  // Vehicle is landing.
	SLUGS_MODE_LOST                  = 7  // Lost connection with vehicle.
	SLUGS_MODE_SELECTIVE_PASSTHROUGH = 8  // Vehicle is in selective passthrough mode, where selected surfaces are being manually controlled.
	SLUGS_MODE_ISR                   = 9  // Vehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message.
	SLUGS_MODE_LINE_PATROL           = 10 // Vehicle is patrolling along lines between waypoints.
	SLUGS_MODE_GROUNDED              = 11 // Vehicle is grounded or an error has occurred.
)

SLUGS_MODE: Slugs-specific navigation modes.

View Source
const (
	CONTROL_SURFACE_FLAG_THROTTLE       = 128 // 0b10000000 Throttle control passes through to pilot console.
	CONTROL_SURFACE_FLAG_LEFT_AILERON   = 64  // 0b01000000 Left aileron control passes through to pilot console.
	CONTROL_SURFACE_FLAG_RIGHT_AILERON  = 32  // 0b00100000 Right aileron control passes through to pilot console.
	CONTROL_SURFACE_FLAG_RUDDER         = 16  // 0b00010000 Rudder control passes through to pilot console.
	CONTROL_SURFACE_FLAG_LEFT_ELEVATOR  = 8   // 0b00001000 Left elevator control passes through to pilot console.
	CONTROL_SURFACE_FLAG_RIGHT_ELEVATOR = 4   // 0b00000100 Right elevator control passes through to pilot console.
	CONTROL_SURFACE_FLAG_LEFT_FLAP      = 2   // 0b00000010 Left flap control passes through to pilot console.
	CONTROL_SURFACE_FLAG_RIGHT_FLAP     = 1   // 0b00000001 Right flap control passes through to pilot console.
)

CONTROL_SURFACE_FLAG: These flags encode the control surfaces for selective passthrough mode. If a bit is set then the pilot console

has control of the surface, and if not then the autopilot has control of the surface.

Variables

This section is empty.

Functions

func Init

func Init()

Init initializes mavlink.ProtocolName, mavlink.ProtocolVersion, and mavlink.MessageFactory.

func MessageNameIDMap

func MessageNameIDMap() map[string]int

MessageNameIDMap returns a map from message name to message ID.

Types

type Boot

type Boot struct {
	Version uint32 // The onboard software version
}

The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. This message allows the sensor and control MCUs to communicate version numbers on startup.

func (*Boot) FieldsString

func (self *Boot) FieldsString() string

func (*Boot) String

func (self *Boot) String() string

func (*Boot) TypeCRCExtra

func (self *Boot) TypeCRCExtra() uint8

func (*Boot) TypeID

func (self *Boot) TypeID() uint8

func (*Boot) TypeName

func (self *Boot) TypeName() string

func (*Boot) TypeSize

func (self *Boot) TypeSize() uint8

type ControlSurface

type ControlSurface struct {
	Mcontrol  float32 // Pending
	Bcontrol  float32 // Order to origin
	Target    uint8   // The system setting the commands
	Idsurface uint8   // ID control surface send 0: throttle 1: aileron 2: elevator 3: rudder
}

Control for surface; pending and order to origin.

func (*ControlSurface) FieldsString

func (self *ControlSurface) FieldsString() string

func (*ControlSurface) String

func (self *ControlSurface) String() string

func (*ControlSurface) TypeCRCExtra

func (self *ControlSurface) TypeCRCExtra() uint8

func (*ControlSurface) TypeID

func (self *ControlSurface) TypeID() uint8

func (*ControlSurface) TypeName

func (self *ControlSurface) TypeName() string

func (*ControlSurface) TypeSize

func (self *ControlSurface) TypeSize() uint8

type CpuLoad

type CpuLoad struct {
	Batvolt  uint16 // Battery Voltage in millivolts
	Sensload uint8  // Sensor DSC Load
	Ctrlload uint8  // Control DSC Load
}

Sensor and DSC control loads.

func (*CpuLoad) FieldsString

func (self *CpuLoad) FieldsString() string

func (*CpuLoad) String

func (self *CpuLoad) String() string

func (*CpuLoad) TypeCRCExtra

func (self *CpuLoad) TypeCRCExtra() uint8

func (*CpuLoad) TypeID

func (self *CpuLoad) TypeID() uint8

func (*CpuLoad) TypeName

func (self *CpuLoad) TypeName() string

func (*CpuLoad) TypeSize

func (self *CpuLoad) TypeSize() uint8

type CtrlSrfcPt

type CtrlSrfcPt struct {
	Bitfieldpt uint16 // Bitfield containing the passthrough configuration, see CONTROL_SURFACE_FLAG ENUM.
	Target     uint8  // The system setting the commands
}

This message sets the control surfaces for selective passthrough mode.

func (*CtrlSrfcPt) FieldsString

func (self *CtrlSrfcPt) FieldsString() string

func (*CtrlSrfcPt) String

func (self *CtrlSrfcPt) String() string

func (*CtrlSrfcPt) TypeCRCExtra

func (self *CtrlSrfcPt) TypeCRCExtra() uint8

func (*CtrlSrfcPt) TypeID

func (self *CtrlSrfcPt) TypeID() uint8

func (*CtrlSrfcPt) TypeName

func (self *CtrlSrfcPt) TypeName() string

func (*CtrlSrfcPt) TypeSize

func (self *CtrlSrfcPt) TypeSize() uint8

type DataLog

type DataLog struct {
	Fl1 float32 // Log value 1
	Fl2 float32 // Log value 2
	Fl3 float32 // Log value 3
	Fl4 float32 // Log value 4
	Fl5 float32 // Log value 5
	Fl6 float32 // Log value 6
}

Configurable data log probes to be used inside Simulink

func (*DataLog) FieldsString

func (self *DataLog) FieldsString() string

func (*DataLog) String

func (self *DataLog) String() string

func (*DataLog) TypeCRCExtra

func (self *DataLog) TypeCRCExtra() uint8

func (*DataLog) TypeID

func (self *DataLog) TypeID() uint8

func (*DataLog) TypeName

func (self *DataLog) TypeName() string

func (*DataLog) TypeSize

func (self *DataLog) TypeSize() uint8

type Diagnostic

type Diagnostic struct {
	Diagfl1 float32 // Diagnostic float 1
	Diagfl2 float32 // Diagnostic float 2
	Diagfl3 float32 // Diagnostic float 3
	Diagsh1 int16   // Diagnostic short 1
	Diagsh2 int16   // Diagnostic short 2
	Diagsh3 int16   // Diagnostic short 3
}

Configurable diagnostic messages.

func (*Diagnostic) FieldsString

func (self *Diagnostic) FieldsString() string

func (*Diagnostic) String

func (self *Diagnostic) String() string

func (*Diagnostic) TypeCRCExtra

func (self *Diagnostic) TypeCRCExtra() uint8

func (*Diagnostic) TypeID

func (self *Diagnostic) TypeID() uint8

func (*Diagnostic) TypeName

func (self *Diagnostic) TypeName() string

func (*Diagnostic) TypeSize

func (self *Diagnostic) TypeSize() uint8

type GpsDateTime

type GpsDateTime struct {
	Year        uint8 // Year reported by Gps
	Month       uint8 // Month reported by Gps
	Day         uint8 // Day reported by Gps
	Hour        uint8 // Hour reported by Gps
	Min         uint8 // Min reported by Gps
	Sec         uint8 // Sec reported by Gps
	Clockstat   uint8 // Clock Status. See table 47 page 211 OEMStar Manual
	Vissat      uint8 // Visible satellites reported by Gps
	Usesat      uint8 // Used satellites in Solution
	Gppgl       uint8 // GPS+GLONASS satellites in Solution
	Sigusedmask uint8 // GPS and GLONASS usage mask (bit 0 GPS_used? bit_4 GLONASS_used?)
	Percentused uint8 // Percent used GPS
}

Pilot console PWM messges.

func (*GpsDateTime) FieldsString

func (self *GpsDateTime) FieldsString() string

func (*GpsDateTime) String

func (self *GpsDateTime) String() string

func (*GpsDateTime) TypeCRCExtra

func (self *GpsDateTime) TypeCRCExtra() uint8

func (*GpsDateTime) TypeID

func (self *GpsDateTime) TypeID() uint8

func (*GpsDateTime) TypeName

func (self *GpsDateTime) TypeName() string

func (*GpsDateTime) TypeSize

func (self *GpsDateTime) TypeSize() uint8

type IsrLocation

type IsrLocation struct {
	Latitude  float32 // ISR Latitude
	Longitude float32 // ISR Longitude
	Height    float32 // ISR Height
	Target    uint8   // The system reporting the action
	Option1   uint8   // Option 1
	Option2   uint8   // Option 2
	Option3   uint8   // Option 3
}

Transmits the position of watch

func (*IsrLocation) FieldsString

func (self *IsrLocation) FieldsString() string

func (*IsrLocation) String

func (self *IsrLocation) String() string

func (*IsrLocation) TypeCRCExtra

func (self *IsrLocation) TypeCRCExtra() uint8

func (*IsrLocation) TypeID

func (self *IsrLocation) TypeID() uint8

func (*IsrLocation) TypeName

func (self *IsrLocation) TypeName() string

func (*IsrLocation) TypeSize

func (self *IsrLocation) TypeSize() uint8

type MidLvlCmds

type MidLvlCmds struct {
	Hcommand float32 // Commanded Altitude in meters
	Ucommand float32 // Commanded Airspeed in m/s
	Rcommand float32 // Commanded Turnrate in rad/s
	Target   uint8   // The system setting the commands
}

Mid Level commands sent from the GS to the autopilot. These are only sent when being operated in mid-level commands mode from the ground.

func (*MidLvlCmds) FieldsString

func (self *MidLvlCmds) FieldsString() string

func (*MidLvlCmds) String

func (self *MidLvlCmds) String() string

func (*MidLvlCmds) TypeCRCExtra

func (self *MidLvlCmds) TypeCRCExtra() uint8

func (*MidLvlCmds) TypeID

func (self *MidLvlCmds) TypeID() uint8

func (*MidLvlCmds) TypeName

func (self *MidLvlCmds) TypeName() string

func (*MidLvlCmds) TypeSize

func (self *MidLvlCmds) TypeSize() uint8

type NovatelDiag

type NovatelDiag struct {
	Receiverstatus uint32  // Status Bitfield. See table 69 page 350 Novatel OEMstar Manual
	Possolage      float32 // Age of the position solution in seconds
	Csfails        uint16  // Times the CRC has failed since boot
	Timestatus     uint8   // The Time Status. See Table 8 page 27 Novatel OEMStar Manual
	Solstatus      uint8   // solution Status. See table 44 page 197
	Postype        uint8   // position type. See table 43 page 196
	Veltype        uint8   // velocity type. See table 43 page 196
}

Transmits the diagnostics data from the Novatel OEMStar GPS

func (*NovatelDiag) FieldsString

func (self *NovatelDiag) FieldsString() string

func (*NovatelDiag) String

func (self *NovatelDiag) String() string

func (*NovatelDiag) TypeCRCExtra

func (self *NovatelDiag) TypeCRCExtra() uint8

func (*NovatelDiag) TypeID

func (self *NovatelDiag) TypeID() uint8

func (*NovatelDiag) TypeName

func (self *NovatelDiag) TypeName() string

func (*NovatelDiag) TypeSize

func (self *NovatelDiag) TypeSize() uint8

type PtzStatus

type PtzStatus struct {
	Pan  int16 // The Pan value in 10ths of degree
	Tilt int16 // The Tilt value in 10ths of degree
	Zoom uint8 // The actual Zoom Value
}

Transmits the actual Pan, Tilt and Zoom values of the camera unit

func (*PtzStatus) FieldsString

func (self *PtzStatus) FieldsString() string

func (*PtzStatus) String

func (self *PtzStatus) String() string

func (*PtzStatus) TypeCRCExtra

func (self *PtzStatus) TypeCRCExtra() uint8

func (*PtzStatus) TypeID

func (self *PtzStatus) TypeID() uint8

func (*PtzStatus) TypeName

func (self *PtzStatus) TypeName() string

func (*PtzStatus) TypeSize

func (self *PtzStatus) TypeSize() uint8

type SensorBias

type SensorBias struct {
	Axbias float32 // Accelerometer X bias (m/s)
	Aybias float32 // Accelerometer Y bias (m/s)
	Azbias float32 // Accelerometer Z bias (m/s)
	Gxbias float32 // Gyro X bias (rad/s)
	Gybias float32 // Gyro Y bias (rad/s)
	Gzbias float32 // Gyro Z bias (rad/s)
}

Accelerometer and gyro biases.

func (*SensorBias) FieldsString

func (self *SensorBias) FieldsString() string

func (*SensorBias) String

func (self *SensorBias) String() string

func (*SensorBias) TypeCRCExtra

func (self *SensorBias) TypeCRCExtra() uint8

func (*SensorBias) TypeID

func (self *SensorBias) TypeID() uint8

func (*SensorBias) TypeName

func (self *SensorBias) TypeName() string

func (*SensorBias) TypeSize

func (self *SensorBias) TypeSize() uint8

type SensorDiag

type SensorDiag struct {
	Float1 float32 // Float field 1
	Float2 float32 // Float field 2
	Int1   int16   // Int 16 field 1
	Char1  int8    // Int 8 field 1
}

Diagnostic data Sensor MCU

func (*SensorDiag) FieldsString

func (self *SensorDiag) FieldsString() string

func (*SensorDiag) String

func (self *SensorDiag) String() string

func (*SensorDiag) TypeCRCExtra

func (self *SensorDiag) TypeCRCExtra() uint8

func (*SensorDiag) TypeID

func (self *SensorDiag) TypeID() uint8

func (*SensorDiag) TypeName

func (self *SensorDiag) TypeName() string

func (*SensorDiag) TypeSize

func (self *SensorDiag) TypeSize() uint8

type SlugsCameraOrder

type SlugsCameraOrder struct {
	Target   uint8 // The system reporting the action
	Pan      int8  // Order the mount to pan: -1 left, 0 No pan motion, +1 right
	Tilt     int8  // Order the mount to tilt: -1 down, 0 No tilt motion, +1 up
	Zoom     int8  // Order the zoom values 0 to 10
	Movehome int8  // Orders the camera mount to move home. The other fields are ignored when this field is set. 1: move home, 0 ignored
}

Orders generated to the SLUGS camera mount.

func (*SlugsCameraOrder) FieldsString

func (self *SlugsCameraOrder) FieldsString() string

func (*SlugsCameraOrder) String

func (self *SlugsCameraOrder) String() string

func (*SlugsCameraOrder) TypeCRCExtra

func (self *SlugsCameraOrder) TypeCRCExtra() uint8

func (*SlugsCameraOrder) TypeID

func (self *SlugsCameraOrder) TypeID() uint8

func (*SlugsCameraOrder) TypeName

func (self *SlugsCameraOrder) TypeName() string

func (*SlugsCameraOrder) TypeSize

func (self *SlugsCameraOrder) TypeSize() uint8

type SlugsConfigurationCamera

type SlugsConfigurationCamera struct {
	Target  uint8 // The system setting the commands
	Idorder uint8 // ID 0: brightness 1: aperture 2: iris 3: ICR 4: backlight
	Order   uint8 //  1: up/on 2: down/off 3: auto/reset/no action
}

Control for camara.

func (*SlugsConfigurationCamera) FieldsString

func (self *SlugsConfigurationCamera) FieldsString() string

func (*SlugsConfigurationCamera) String

func (self *SlugsConfigurationCamera) String() string

func (*SlugsConfigurationCamera) TypeCRCExtra

func (self *SlugsConfigurationCamera) TypeCRCExtra() uint8

func (*SlugsConfigurationCamera) TypeID

func (self *SlugsConfigurationCamera) TypeID() uint8

func (*SlugsConfigurationCamera) TypeName

func (self *SlugsConfigurationCamera) TypeName() string

func (*SlugsConfigurationCamera) TypeSize

func (self *SlugsConfigurationCamera) TypeSize() uint8

type SlugsMobileLocation

type SlugsMobileLocation struct {
	Latitude  float32 // Mobile Latitude
	Longitude float32 // Mobile Longitude
	Target    uint8   // The system reporting the action
}

Transmits the last known position of the mobile GS to the UAV. Very relevant when Track Mobile is enabled

func (*SlugsMobileLocation) FieldsString

func (self *SlugsMobileLocation) FieldsString() string

func (*SlugsMobileLocation) String

func (self *SlugsMobileLocation) String() string

func (*SlugsMobileLocation) TypeCRCExtra

func (self *SlugsMobileLocation) TypeCRCExtra() uint8

func (*SlugsMobileLocation) TypeID

func (self *SlugsMobileLocation) TypeID() uint8

func (*SlugsMobileLocation) TypeName

func (self *SlugsMobileLocation) TypeName() string

func (*SlugsMobileLocation) TypeSize

func (self *SlugsMobileLocation) TypeSize() uint8

type SlugsNavigation

type SlugsNavigation struct {
	UM        float32 // Measured Airspeed prior to the nav filter in m/s
	PhiC      float32 // Commanded Roll
	ThetaC    float32 // Commanded Pitch
	PsidotC   float32 // Commanded Turn rate
	AyBody    float32 // Y component of the body acceleration
	Totaldist float32 // Total Distance to Run on this leg of Navigation
	Dist2go   float32 // Remaining distance to Run on this leg of Navigation
	HC        uint16  // Commanded altitude in 0.1 m
	Fromwp    uint8   // Origin WP
	Towp      uint8   // Destination WP
}

Data used in the navigation algorithm.

func (*SlugsNavigation) FieldsString

func (self *SlugsNavigation) FieldsString() string

func (*SlugsNavigation) String

func (self *SlugsNavigation) String() string

func (*SlugsNavigation) TypeCRCExtra

func (self *SlugsNavigation) TypeCRCExtra() uint8

func (*SlugsNavigation) TypeID

func (self *SlugsNavigation) TypeID() uint8

func (*SlugsNavigation) TypeName

func (self *SlugsNavigation) TypeName() string

func (*SlugsNavigation) TypeSize

func (self *SlugsNavigation) TypeSize() uint8

type StatusGps

type StatusGps struct {
	Magvar     float32 // Magnetic variation, degrees
	Csfails    uint16  // Number of times checksum has failed
	Gpsquality uint8   // The quality indicator, 0=fix not available or invalid, 1=GPS fix, 2=C/A differential GPS, 6=Dead reckoning mode, 7=Manual input mode (fixed position), 8=Simulator mode, 9= WAAS a
	Msgstype   uint8   //  Indicates if GN, GL or GP messages are being received
	Posstatus  uint8   //  A = data valid, V = data invalid
	Magdir     int8    //  Magnetic variation direction E/W. Easterly variation (E) subtracts from True course and Westerly variation (W) adds to True course
	Modeind    uint8   //  Positioning system mode indicator. A - Autonomous;D-Differential; E-Estimated (dead reckoning) mode;M-Manual input; N-Data not valid
}

This contains the status of the GPS readings

func (*StatusGps) FieldsString

func (self *StatusGps) FieldsString() string

func (*StatusGps) String

func (self *StatusGps) String() string

func (*StatusGps) TypeCRCExtra

func (self *StatusGps) TypeCRCExtra() uint8

func (*StatusGps) TypeID

func (self *StatusGps) TypeID() uint8

func (*StatusGps) TypeName

func (self *StatusGps) TypeName() string

func (*StatusGps) TypeSize

func (self *StatusGps) TypeSize() uint8

type UavStatus

type UavStatus struct {
	Latitude  float32 // Latitude UAV
	Longitude float32 // Longitude UAV
	Altitude  float32 // Altitude UAV
	Speed     float32 // Speed UAV
	Course    float32 // Course UAV
	Target    uint8   // The ID system reporting the action
}

Transmits the actual status values UAV in flight

func (*UavStatus) FieldsString

func (self *UavStatus) FieldsString() string

func (*UavStatus) String

func (self *UavStatus) String() string

func (*UavStatus) TypeCRCExtra

func (self *UavStatus) TypeCRCExtra() uint8

func (*UavStatus) TypeID

func (self *UavStatus) TypeID() uint8

func (*UavStatus) TypeName

func (self *UavStatus) TypeName() string

func (*UavStatus) TypeSize

func (self *UavStatus) TypeSize() uint8

type VoltSensor

type VoltSensor struct {
	Voltage  uint16 // Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V
	Reading2 uint16 // Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value
	R2type   uint8  // It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM
}

Transmits the readings from the voltage and current sensors

func (*VoltSensor) FieldsString

func (self *VoltSensor) FieldsString() string

func (*VoltSensor) String

func (self *VoltSensor) String() string

func (*VoltSensor) TypeCRCExtra

func (self *VoltSensor) TypeCRCExtra() uint8

func (*VoltSensor) TypeID

func (self *VoltSensor) TypeID() uint8

func (*VoltSensor) TypeName

func (self *VoltSensor) TypeName() string

func (*VoltSensor) TypeSize

func (self *VoltSensor) TypeSize() uint8

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL