Documentation ¶
Overview ¶
Package tmcstepper implements a TMC stepper motor.
Index ¶
- Constants
- func NewMotor(ctx context.Context, deps registry.Dependencies, c TMC5072Config, ...) (motor.LocalMotor, error)
- type Motor
- func (m *Motor) AtVelocity(ctx context.Context) (bool, error)
- func (m *Motor) DoCommand(ctx context.Context, cmd map[string]interface{}) (map[string]interface{}, error)
- func (m *Motor) Enable(ctx context.Context, turnOn bool) error
- func (m *Motor) GetSG(ctx context.Context) (int32, error)
- func (m *Motor) GoFor(ctx context.Context, rpm, rotations float64, extra map[string]interface{}) error
- func (m *Motor) GoTillStop(ctx context.Context, rpm float64, stopFunc func(ctx context.Context) bool) error
- func (m *Motor) GoTo(ctx context.Context, rpm, positionRevolutions float64, ...) error
- func (m *Motor) Home(ctx context.Context) error
- func (m *Motor) IsMoving(ctx context.Context) (bool, error)
- func (m *Motor) IsPowered(ctx context.Context, extra map[string]interface{}) (bool, error)
- func (m *Motor) IsStopped(ctx context.Context) (bool, error)
- func (m *Motor) Jog(ctx context.Context, rpm float64) error
- func (m *Motor) Position(ctx context.Context, extra map[string]interface{}) (float64, error)
- func (m *Motor) Properties(ctx context.Context, extra map[string]interface{}) (map[motor.Feature]bool, error)
- func (m *Motor) ResetZeroPosition(ctx context.Context, offset float64, extra map[string]interface{}) error
- func (m *Motor) SetPower(ctx context.Context, powerPct float64, extra map[string]interface{}) error
- func (m *Motor) Stop(ctx context.Context, extra map[string]interface{}) error
- type PinConfig
- type TMC5072Config
Constants ¶
const ( Command = "command" Home = "home" Jog = "jog" RPMVal = "rpm" )
DoCommand() related constants.
Variables ¶
This section is empty.
Functions ¶
func NewMotor ¶
func NewMotor(ctx context.Context, deps registry.Dependencies, c TMC5072Config, logger golog.Logger) (motor.LocalMotor, error)
NewMotor returns a TMC5072 driven motor.
Types ¶
type Motor ¶
type Motor struct {
// contains filtered or unexported fields
}
A Motor represents a brushless motor connected via a TMC controller chip (ex: TMC5072).
func (*Motor) AtVelocity ¶
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 ¶
Enable pulls down the hardware enable pin, activating the power stage of the chip.
func (*Motor) GetSG ¶
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) GoTillStop ¶
func (m *Motor) GoTillStop(ctx context.Context, rpm float64, stopFunc func(ctx context.Context) bool) error
GoTillStop enables StallGuard detection, then moves in the direction/speed given until resistance (endstop) is detected.
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) Properties ¶
func (m *Motor) Properties(ctx context.Context, extra map[string]interface{}) (map[motor.Feature]bool, error)
Properties returns the status of optional features 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.
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"` BoardName string `json:"board"` // used to get encoders MaxRPM float64 `json:"max_rpm,omitempty"` // RPM MaxAcceleration float64 `json:"max_acceleration,omitempty"` // RPM per second 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.