kinematicbase

package
v0.15.0-rc0 Latest Latest
Warning

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

Go to latest
Published: Nov 28, 2023 License: AGPL-3.0 Imports: 18 Imported by: 2

Documentation

Overview

Package kinematicbase contains wrappers that augment bases with information needed for higher level control over the base

Package kinematicbase contains wrappers that augment bases with information needed for higher level control over the base

Package kinematicbase contains wrappers that augment bases with information needed for higher level control over the base

Index

Constants

This section is empty.

Variables

View Source
var ErrMovementTimeout = errors.New("movement has timed out")

ErrMovementTimeout is used for when a movement call times out after no movement for some time.

Functions

This section is empty.

Types

type KinematicBase

type KinematicBase interface {
	base.Base
	motion.Localizer
	referenceframe.InputEnabled

	Kinematics() referenceframe.Frame
	// ErrorState takes a complete motionplan, as well as the index of the currently-executing set of inputs, and computes the pose
	// difference between where the robot in fact is, and where it ought to be.
	ErrorState(context.Context, [][]referenceframe.Input, int) (spatialmath.Pose, error)
}

KinematicBase is an interface for Bases that also satisfy the ModelFramer and InputEnabled interfaces.

func WrapWithFakeDiffDriveKinematics added in v0.10.0

func WrapWithFakeDiffDriveKinematics(
	ctx context.Context,
	b *fake.Base,
	localizer motion.Localizer,
	limits []referenceframe.Limit,
	options Options,
	sensorNoise spatialmath.Pose,
) (KinematicBase, error)

WrapWithFakeDiffDriveKinematics creates a DiffDrive KinematicBase from the fake Base so that it satisfies the ModelFramer and InputEnabled interfaces.

func WrapWithFakePTGKinematics added in v0.10.0

func WrapWithFakePTGKinematics(
	ctx context.Context,
	b *fake.Base,
	logger logging.Logger,
	origin *referenceframe.PoseInFrame,
	options Options,
	sensorNoise spatialmath.Pose,
	sleepTime int,
) (KinematicBase, error)

WrapWithFakePTGKinematics creates a PTG KinematicBase from the fake Base so that it satisfies the ModelFramer and InputEnabled interfaces.

func WrapWithKinematics added in v0.4.0

func WrapWithKinematics(
	ctx context.Context,
	b base.Base,
	logger logging.Logger,
	localizer motion.Localizer,
	limits []referenceframe.Limit,
	options Options,
) (KinematicBase, error)

WrapWithKinematics will wrap a Base with the appropriate type of kinematics, allowing it to provide a Frame which can be planned with and making it InputEnabled.

type Options added in v0.7.0

type Options struct {
	// LinearVelocityMMPerSec is the linear velocity the base will drive at in mm/s
	LinearVelocityMMPerSec float64

	// AngularVelocityMMPerSec is the angular velocity the base will turn with in deg/s
	AngularVelocityDegsPerSec float64

	// GoalRadiusMM is used when the base is moving to a goal. It is considered successful if it is within this radius.
	GoalRadiusMM float64

	// HeadingThresholdDegrees is used when the base is moving to a goal.
	// If its heading is within this angle it is considered to be on the correct path.
	HeadingThresholdDegrees float64

	// PlanDeviationThresholdMM is the amount that the base is allowed to deviate from the straight line path it is intended to travel.
	// If it ever exceeds this amount the movement will fail and an error will be returned.
	PlanDeviationThresholdMM float64

	// Timeout is the maximum amount of time that the base is allowed to remain stationary during a movement, else an error is thrown.
	Timeout time.Duration

	// MinimumMovementThresholdMM is the amount that a base needs to move for it not to be considered stationary.
	MinimumMovementThresholdMM float64

	// MaxMoveStraightMM is the maximum distance the base should move with a single MoveStraight command.
	// used to break up large driving segments to prevent error from building up due to slightly incorrect angle.
	MaxMoveStraightMM float64

	// MaxSpinAngleDeg is the maximum amount of degrees the base should turn with a single Spin command.
	// used to break up large turns into smaller chunks to prevent error from building up.
	MaxSpinAngleDeg float64

	// PositionOnlyMode defines whether motion planning should be done in 2DOF or 3DOF.
	// If value is true, planning is done in [x,y]. If value is false, planning is done in [x,y,theta].
	PositionOnlyMode bool

	// UsePTGs defines whether motion planning should plan using PTGs.
	UsePTGs bool

	// NoSkidSteer defines whether motion planning should plan for diff drive bases using skid steer. If true, it will plan using
	// only rotations and straight lines. Not used if turning radius > 0, or if UsePTGs is false.
	NoSkidSteer bool
}

Options contains values used for execution of base movement.

func NewKinematicBaseOptions added in v0.7.0

func NewKinematicBaseOptions() Options

NewKinematicBaseOptions creates a struct with values used for execution of base movement. all values are pre-set to reasonable default values and can be changed if desired.

Jump to

Keyboard shortcuts

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