tmcstepper

package
v0.32.0-rc1 Latest Latest
Warning

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

Go to latest
Published: Jul 8, 2024 License: AGPL-3.0 Imports: 12 Imported by: 0

Documentation

Overview

Package tmcstepper implements a TMC stepper motor.

Package tmcstepper is only implemented on Linux.

Index

Constants

View Source
const (
	Command = "command"
	Home    = "home"
	Jog     = "jog"
	RPMVal  = "rpm"
)

DoCommand() related constants.

Variables

This section is empty.

Functions

This section is empty.

Types

type Motor

type Motor struct {
	resource.Named
	resource.AlwaysRebuild
	resource.TriviallyCloseable
	// contains filtered or unexported fields
}

A Motor represents a brushless motor connected via a TMC controller chip (ex: TMC5072).

func (*Motor) AtVelocity

func (m *Motor) AtVelocity(ctx context.Context) (bool, error)

AtVelocity returns true if the motor has reached the requested velocity.

func (*Motor) DoCommand

func (m *Motor) DoCommand(ctx context.Context, cmd map[string]interface{}) (map[string]interface{}, error)

DoCommand executes additional commands beyond the Motor{} interface.

func (*Motor) Enable

func (m *Motor) Enable(ctx context.Context, turnOn bool) error

Enable pulls down the hardware enable pin, activating the power stage of the chip.

func (*Motor) GetSG

func (m *Motor) GetSG(ctx context.Context) (int32, error)

GetSG returns the current StallGuard reading (effectively an indication of motor load.)

func (*Motor) GoFor

func (m *Motor) GoFor(ctx context.Context, rpm, rotations float64, extra map[string]interface{}) error

GoFor turns in the given direction the given number of times at the given speed. Both the RPM and the revolutions can be assigned negative values to move in a backwards direction. Note: if both are negative the motor will spin in the forward direction.

func (*Motor) GoTo

func (m *Motor) GoTo(ctx context.Context, rpm, positionRevolutions float64, extra map[string]interface{}) error

GoTo moves to the specified position in terms of (provided in revolutions from home/zero), at a specific speed. Regardless of the directionality of the RPM this function will move the motor towards the specified target.

func (*Motor) IsMoving

func (m *Motor) IsMoving(ctx context.Context) (bool, error)

IsMoving returns true if the motor is currently moving.

func (*Motor) IsPowered

func (m *Motor) IsPowered(ctx context.Context, extra map[string]interface{}) (bool, float64, error)

IsPowered returns true if the motor is currently moving.

func (*Motor) IsStopped

func (m *Motor) IsStopped(ctx context.Context) (bool, error)

IsStopped returns true if the motor is NOT moving.

func (*Motor) Jog

func (m *Motor) Jog(ctx context.Context, rpm float64) error

Jog sets a fixed RPM.

func (*Motor) Position

func (m *Motor) Position(ctx context.Context, extra map[string]interface{}) (float64, error)

Position gives the current motor position.

func (*Motor) Properties

func (m *Motor) Properties(ctx context.Context, extra map[string]interface{}) (motor.Properties, error)

Properties returns the status of optional properties on the motor.

func (*Motor) ResetZeroPosition

func (m *Motor) ResetZeroPosition(ctx context.Context, offset float64, extra map[string]interface{}) error

ResetZeroPosition sets the current position of the motor specified by the request (adjusted by a given offset) to be its new zero position.

func (*Motor) SetPower

func (m *Motor) SetPower(ctx context.Context, powerPct float64, extra map[string]interface{}) error

SetPower sets the motor at a particular rpm based on the percent of maxRPM supplied by powerPct (between -1 and 1).

func (*Motor) SetRPM added in v0.29.0

func (m *Motor) SetRPM(ctx context.Context, rpm float64, extra map[string]interface{}) error

SetRPM instructs the motor to move at the specified RPM indefinitely.

func (*Motor) Stop

func (m *Motor) Stop(ctx context.Context, extra map[string]interface{}) error

Stop stops the motor.

type PinConfig

type PinConfig struct {
	EnablePinLow string `json:"en_low,omitempty"`
}

PinConfig defines the mapping of where motor are wired.

type TMC5072Config

type TMC5072Config struct {
	Pins             PinConfig `json:"pins,omitempty"`
	BoardName        string    `json:"board,omitempty"` // used solely for the PinConfig
	MaxRPM           float64   `json:"max_rpm,omitempty"`
	MaxAcceleration  float64   `json:"max_acceleration_rpm_per_sec,omitempty"`
	TicksPerRotation int       `json:"ticks_per_rotation"`
	SPIBus           string    `json:"spi_bus"`
	ChipSelect       string    `json:"chip_select"`
	Index            int       `json:"index"`
	SGThresh         int32     `json:"sg_thresh,omitempty"`
	HomeRPM          float64   `json:"home_rpm,omitempty"`
	CalFactor        float64   `json:"cal_factor,omitempty"`
	RunCurrent       int32     `json:"run_current,omitempty"`  // 1-32 as a percentage of rsense voltage, 15 default
	HoldCurrent      int32     `json:"hold_current,omitempty"` // 1-32 as a percentage of rsense voltage, 8 default
	HoldDelay        int32     `json:"hold_delay,omitempty"`   // 0=instant powerdown, 1-15=delay * 2^18 clocks, 6 default
}

TMC5072Config describes the configuration of a motor.

func (*TMC5072Config) Validate added in v0.1.6

func (config *TMC5072Config) Validate(path string) ([]string, error)

Validate ensures all parts of the config are valid.

Jump to

Keyboard shortcuts

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