pipoint

package module
v0.0.0-...-87985d3 Latest Latest
Warning

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

Go to latest
Published: Oct 22, 2018 License: Apache-2.0 Imports: 12 Imported by: 0

README

pipoint - a PX4 based camera pointer.

Some time ago I set up a camera, pointed it at the sky, and recorded as I flew my model plane about. It was quite cool, but the plane covers so much area that most of the video was of blue sky.

PiPoint solves this problem by automatically pointing a ground based camera at the rover using GPS, a telemtry link, and pan/tilt unit.

Implementation

Overview

The system consists of:

On the rover:

In the base station:

Assembling this is left as an exercise for the reader :) There are some photos on my blog.

Build

  • See hardware/ and https://www.tinkercad.com/dashboard/search?q=pipoint for the camera adapter.
  • See ansible/ for rules to set up the Raspberry Pi.
  • See etc/ for files used on the PX4 or Raspberry Pi. Copy extra.txt to etc/extra.txt on the PixFalcon SD card.
  • See Makefile for shortcuts to build pipoint itself.

Note

This is not an official Google product.

-- Michael Hope michaelh@juju.nz mlhx@google.com

Documentation

Index

Examples

Constants

This section is empty.

Variables

View Source
var (
	// Version is the overall binary version.  Set from the
	// build.
	Version = "dev"
)

Functions

func AsDeg

func AsDeg(rad float64) float64

AsDeg converts radians to degrees.

func AsRad

func AsRad(deg float64) float64

AsRad converts degrees to radians.

func LatLength

func LatLength(lat float64) float64

LatLength returns the length of a line of latitude at the given latitude. Input is in rad, output in m.

Example
fmt.Println(int(LatLength(46.8 * math.Pi / 180)))
Output:

111166

func LonLength

func LonLength(lat float64) float64

LonLength returns the length of a line of longitude at the given latitude. Input is in rad, output in m.

Types

type Attitude

type Attitude struct {
	Roll  float64
	Pitch float64
	Yaw   float64
}

Attitude is the orientation of a body, often to the local tangent plane.

type AudioOut

type AudioOut struct {
	// contains filtered or unexported fields
}

AudioOut can play files or speech.

func NewAudioOut

func NewAudioOut() *AudioOut

NewAudioOut creates a new, running audio output.

func (*AudioOut) Play

func (a *AudioOut) Play(path string)

Play plays an audio file.

func (*AudioOut) Say

func (a *AudioOut) Say(text string)

Say plays a pre-recorded phrase, or falls back to espeak.

type CycleState

type CycleState struct {
	// contains filtered or unexported fields
}

CycleState cycles the pan/tilt in a circle.

func (*CycleState) Name

func (s *CycleState) Name() string

func (*CycleState) Update

func (s *CycleState) Update(param *param.Param)

Update reacts to changes in parameters.

type EventLogger

type EventLogger struct {
	// contains filtered or unexported fields
}

EventLogger is a async event logger.

func NewEventLogger

func NewEventLogger(name string) *EventLogger

NewEventLogger creates a new event logger that writes to the given base name.

func (*EventLogger) Write

func (el *EventLogger) Write(p []byte) (n int, err error)

type HoldState

type HoldState struct {
	// contains filtered or unexported fields
}

HoldState executes when the camera is tracking the rover.

func (*HoldState) Name

func (s *HoldState) Name() string

func (*HoldState) Update

func (s *HoldState) Update(param *param.Param)

Update is called when a param is updated.

type LinPred

type LinPred struct {
	// contains filtered or unexported fields
}

LinPred is a velocity based linear predictive filter.

func (*LinPred) GetEx

func (l *LinPred) GetEx(now float64) float64

GetEx returns the predicted measurement based on the given local time.

func (*LinPred) SetEx

func (l *LinPred) SetEx(x, now, stamp float64)

SetEx is called when a new measurement arrives. x is the measurement, now is the local time this function was called, and stamp is the sensor specific time the measurement was made.

The velocity is calculated based on sensor time. The prediction is based on local time.

type LocateState

type LocateState struct {
	// contains filtered or unexported fields
}

LocateState runs initially to locate the base unit.

func (*LocateState) Name

func (s *LocateState) Name() string

func (*LocateState) Update

func (s *LocateState) Update(param *param.Param)

Update is called when a param is updated.

type Lowpass

type Lowpass struct {
	// The current filter output.
	Acc float64
}

Lowpass is a first order low pass filter.

func (*Lowpass) StepEx

func (l *Lowpass) StepEx(v, tau float64) float64

StepEx feeds v into the filter and returns the filtered value. Tau is the filter coefficient, where 1.0 is no filtering and 0.0 is no pass through.

type NEUPosition

type NEUPosition struct {
	Time  float64
	North float64
	East  float64
	Up    float64
}

NEUPosition is a 3D point on the local tangent plane.

func (*NEUPosition) Add

func (p *NEUPosition) Add(right *NEUPosition) *NEUPosition

Add returns piecewise this plus right.

func (*NEUPosition) Sub

func (p *NEUPosition) Sub(right *NEUPosition) *NEUPosition

Sub returns piecewise this minus right.

type OrientateState

type OrientateState struct {
	// contains filtered or unexported fields
}

OrientateState runs to set the pan orientation.

func (*OrientateState) Name

func (s *OrientateState) Name() string

func (*OrientateState) Update

func (s *OrientateState) Update(param *param.Param)

Update is called when a param is updated.

type PiPoint

type PiPoint struct {
	Params *param.Params
	// contains filtered or unexported fields
}

PiPoint is an automatic, GPS based system that points a camera at the rover.

func NewPiPoint

func NewPiPoint() *PiPoint

NewPiPoint creates a new camera pointer.

func (*PiPoint) AddMQTT

func (pi *PiPoint) AddMQTT(mqtt *mqtt.Adaptor)

AddMQTT adds a new MQTT connection that bridges between MQTT and params.

func (*PiPoint) Message

func (pi *PiPoint) Message(msg interface{})

Message handles a MAVLink message.

func (*PiPoint) Run

func (pi *PiPoint) Run()

Run is the main entry point that runs forever.

type Position

type Position struct {
	Time    float64
	Lat     float64
	Lon     float64
	Alt     float64
	Heading float64
}

Position is a 3D point in geographic coordinates.

func (*Position) ToNEU

func (p *Position) ToNEU() *NEUPosition

ToNEU converts a geographic position to local tangent plane.

type PwmPin

type PwmPin struct {
	Chip int
	Pin  int
}

PwmPin represents a single pin on sysfs.

func (*PwmPin) Export

func (p *PwmPin) Export() (err error)

Export exports this pin.

func (*PwmPin) SetDuty

func (p *PwmPin) SetDuty(duty int) (err error)

SetDuty sets the on time in ns. Should be less than the period.

func (*PwmPin) SetEnable

func (p *PwmPin) SetEnable(val int) (err error)

SetEnable enables or disables the PWM output.

func (*PwmPin) SetPeriod

func (p *PwmPin) SetPeriod(period int) (err error)

SetPeriod sets the PWM period in ns.

func (*PwmPin) UnExport

func (p *PwmPin) UnExport() (err error)

UnExport removes the export for this pin.

type RunState

type RunState struct {
	// contains filtered or unexported fields
}

RunState executes when the camera is tracking the rover.

func (*RunState) Name

func (s *RunState) Name() string

func (*RunState) Update

func (s *RunState) Update(param *param.Param)

Update is called when a param is updated.

type Servo

type Servo struct {
	// contains filtered or unexported fields
}

Servo is a servo on a pin with limits, demand, and actual position.

func NewServo

func NewServo(name string, params *param.Params) *Servo

NewServo creates a new servo with params on the given tree.

func (*Servo) Set

func (s *Servo) Set(angle float64)

Set updates the target angle in radians. The servo is actually updated on calling Tick().

func (*Servo) Tick

func (s *Servo) Tick()

Tick updates the servo output based on demand. Call every ~20 ms.

type ServoBlaster

type ServoBlaster struct {
	Pin int
}

func (*ServoBlaster) SetDuty

func (s *ServoBlaster) SetDuty(period int) (err error)

SetDuty sets the servo period in ns.

type ServoParams

type ServoParams struct {
	Pin  int
	Span float64

	Min  float64
	Max  float64
	Low  float64
	High float64

	Tau float64
}

ServoParams holds the parameters for a servo including limits.

type State

type State interface {
	Name() string
	Update(param *param.Param)
}

State is a handler for the current state of the system.

Directories

Path Synopsis

Jump to

Keyboard shortcuts

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