Documentation ¶
Overview ¶
Package motor contains a gRPC bases motor client
Package motor contains an enum representing optional motor features ¶
Package motor contains a gRPC based motor service server
Index ¶
- Constants
- Variables
- func CreateStatus(ctx context.Context, resource interface{}) (*pb.Status, error)
- func FeatureMapToProtoResponse(featureMap map[Feature]bool) (*pb.GetFeaturesResponse, error)
- func Named(name string) resource.Name
- func NamesFromRobot(r robot.Robot) []string
- func NewFeatureUnsupportedError(feature Feature, motorName string) error
- func NewGoTillStopUnsupportedError(motorName string) error
- func NewResetZeroPositionUnsupportedError(motorName string) error
- func NewServer(service subtype.Service) pb.MotorServiceServer
- func ProtoFeaturesToMap(resp *pb.GetFeaturesResponse) map[Feature]bool
- func RegisterConfigAttributeConverter(model string)
- func WrapWithReconfigurable(r interface{}) (resource.Reconfigurable, error)
- type Config
- type Feature
- type LocalMotor
- type Motor
- type PinConfig
- type Position
- type Powered
Constants ¶
const SubtypeName = resource.SubtypeName("motor")
SubtypeName is a constant that identifies the component resource subtype string "motor".
Variables ¶
var Subtype = resource.NewSubtype( resource.ResourceNamespaceRDK, resource.ResourceTypeComponent, SubtypeName, )
Subtype is a constant that identifies the component resource subtype.
Functions ¶
func CreateStatus ¶
CreateStatus creates a status from the motor.
func FeatureMapToProtoResponse ¶
func FeatureMapToProtoResponse( featureMap map[Feature]bool, ) (*pb.GetFeaturesResponse, error)
FeatureMapToProtoResponse takes a map of features to booleans (indicating whether the feature is supported) and converts it to a GetFeaturesResponse.
func NamesFromRobot ¶
NamesFromRobot is a helper for getting all motor names from the given Robot.
func NewFeatureUnsupportedError ¶
NewFeatureUnsupportedError returns an error representing the need for a motor to support a particular feature.
func NewGoTillStopUnsupportedError ¶
NewGoTillStopUnsupportedError returns a standard error for when a motor is required to support the GoTillStop feature.
func NewResetZeroPositionUnsupportedError ¶
NewResetZeroPositionUnsupportedError returns a standard error for when a motor is required to support reseting the zero position.
func NewServer ¶
func NewServer(service subtype.Service) pb.MotorServiceServer
NewServer constructs a motor gRPC service server.
func ProtoFeaturesToMap ¶
func ProtoFeaturesToMap(resp *pb.GetFeaturesResponse) map[Feature]bool
ProtoFeaturesToMap takes a GetFeaturesResponse and returns an equivalent Feature-to-boolean map.
func RegisterConfigAttributeConverter ¶
func RegisterConfigAttributeConverter(model string)
RegisterConfigAttributeConverter registers a Config converter. Note(erd): This probably shouldn't exist since not all motors have the same config requirements.
func WrapWithReconfigurable ¶
func WrapWithReconfigurable(r interface{}) (resource.Reconfigurable, error)
WrapWithReconfigurable converts a regular Motor implementation to a reconfigurableMotor. If motor is already a reconfigurableMotor, then nothing is done.
Types ¶
type Config ¶
type Config struct { Pins PinConfig `json:"pins"` BoardName string `json:"board"` // used to get encoders MinPowerPct float64 `json:"min_power_pct,omitempty"` // min power percentage to allow for this motor default is 0.0 MaxPowerPct float64 `json:"max_power_pct,omitempty"` // max power percentage to allow for this motor (0.06 - 1.0) PWMFreq uint `json:"pwm_freq,omitempty"` DirectionFlip bool `json:"dir_flip,omitempty"` // Flip the direction of the signal sent if there is a Dir pin StepperDelay uint `json:"stepper_delay,omitempty"` // When using stepper motors, the time to remain high ControlLoop control.ControlConfig `json:"control_config,omitempty"` // Optional control loop Encoder string `json:"encoder,omitempty"` // name of encoder RampRate float64 `json:"ramp_rate,omitempty"` // how fast to ramp power to motor when using rpm control MaxRPM float64 `json:"max_rpm,omitempty"` // RPM MaxAcceleration float64 `json:"max_acceleration,omitempty"` // RPM per second TicksPerRotation int `json:"ticks_per_rotation,omitempty"` }
Config describes the configuration of a motor.
type Feature ¶
type Feature string
Feature is an enum representing an optional motor feature.
const PositionReporting Feature = "PositionReporting"
PositionReporting represesnts the feature of a motor being able to report its own position.
type LocalMotor ¶
type LocalMotor interface { Motor // GoTillStop moves a motor until stopped. The "stop" mechanism is up to the underlying motor implementation. // Ex: EncodedMotor goes until physically stopped/stalled (detected by change in position being very small over a fixed time.) // Ex: TMCStepperMotor has "StallGuard" which detects the current increase when obstructed and stops when that reaches a threshold. // Ex: Other motors may use an endstop switch (such as via a DigitalInterrupt) or be configured with other sensors. GoTillStop(ctx context.Context, rpm float64, stopFunc func(ctx context.Context) bool) error resource.MovingCheckable }
A LocalMotor is a motor that supports additional features provided by RDK (e.g. GoTillStop).
type Motor ¶
type Motor interface { // SetPower sets the percentage of power the motor should employ between -1 and 1. // Negative power implies a backward directional rotational SetPower(ctx context.Context, powerPct float64, extra map[string]interface{}) error // GoFor instructs the motor to go in a specific direction for a specific amount of // revolutions at a given speed in revolutions per minute. 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. // If revolutions is 0, this will run the motor at rpm indefinitely // If revolutions != 0, this will block until the number of revolutions has been completed or another operation comes in. GoFor(ctx context.Context, rpm float64, revolutions float64, extra map[string]interface{}) error // GoTo instructs the motor to go to a specific position (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/position // This will block until the position has been reached GoTo(ctx context.Context, rpm float64, positionRevolutions float64, extra map[string]interface{}) error // Set the current position (+/- offset) to be the new zero (home) position. ResetZeroPosition(ctx context.Context, offset float64, extra map[string]interface{}) error // GetPosition reports the position of the motor based on its encoder. If it's not supported, the returned // data is undefined. The unit returned is the number of revolutions which is intended to be fed // back into calls of GoFor. GetPosition(ctx context.Context, extra map[string]interface{}) (float64, error) // GetFeatures returns whether or not the motor supports certain optional features. GetFeatures(ctx context.Context, extra map[string]interface{}) (map[Feature]bool, error) // Stop turns the power to the motor off immediately, without any gradual step down. Stop(ctx context.Context, extra map[string]interface{}) error // IsPowered returns whether or not the motor is currently on. IsPowered(ctx context.Context, extra map[string]interface{}) (bool, error) generic.Generic }
A Motor represents a physical motor connected to a board.
func FromDependencies ¶
func FromDependencies(deps registry.Dependencies, name string) (Motor, error)
FromDependencies is a helper for getting the named motor from a collection of dependencies.
func NewClientFromConn ¶
func NewClientFromConn(ctx context.Context, conn rpc.ClientConn, name string, logger golog.Logger) Motor
NewClientFromConn constructs a new Client from connection passed in.
type PinConfig ¶
type PinConfig struct { A string `json:"a"` B string `json:"b"` Direction string `json:"dir"` PWM string `json:"pwm"` EnablePinHigh string `json:"en_high,omitempty"` EnablePinLow string `json:"en_low,omitempty"` Step string `json:"step,omitempty"` }
PinConfig defines the mapping of where motor are wired. Standard Configurations: - A/B EnablePinHigh/EnablePinLow - A/B + PWM EnablePinHigh/EnablePinLow - Dir + PWM EnablePinHigh/EnablePinLow.
Source Files ¶
Directories ¶
Path | Synopsis |
---|---|
Package dmc4000 implements stepper motors behind a Galil DMC4000 series motor controller
|
Package dmc4000 implements stepper motors behind a Galil DMC4000 series motor controller |
Package ezopmp is a motor driver for the hydrogarden pump
|
Package ezopmp is a motor driver for the hydrogarden pump |
Package fake implements a fake motor.
|
Package fake implements a fake motor. |
Package gpio implements a GPIO based motor.
|
Package gpio implements a GPIO based motor. |
Package gpiostepper implements a GPIO based stepper motor.
|
Package gpiostepper implements a GPIO based stepper motor. |
Package register registers all relevant motors
|
Package register registers all relevant motors |
Package roboclaw is the driver for the roboclaw motor drivers
|
Package roboclaw is the driver for the roboclaw motor drivers |
Package tmcstepper implements a TMC stepper motor.
|
Package tmcstepper implements a TMC stepper motor. |