2#ifndef _CARTESIANROBOT_H
3#define _CARTESIANROBOT_H
6#if defined(HAS_CARTESIAN_ROBOT)
31 constexpr double pi = 3.1415926535897932384626433832795028841971693993751;
102 template<
typename ContainerClass>
103 class RSI_API RapidVectorIterator
107 typedef typename ContainerClass::ValueType ValueType;
110 typedef typename ContainerClass::PointerType PointerType;
114 ValueType& operator*();
118 const ValueType& operator*()
const;
122 RapidVectorIterator& operator++();
126 RapidVectorIterator operator++(
int);
130 bool operator==(
const RapidVectorIterator&)
const;
134 bool operator!=(
const RapidVectorIterator&)
const;
137 RapidVectorIterator(PointerType pointerArgument, PointerType startArgument,
const size_t containerSize);
140 RapidVectorIterator(
const RapidVectorIterator&) =
default;
143 RapidVectorIterator& operator=(
const RapidVectorIterator&) =
default;
146 RapidVectorIterator(RapidVectorIterator&&) noexcept = default;
149 RapidVectorIterator& operator=(RapidVectorIterator&&) noexcept = default;
152 PointerType start, end;
153 void VerifyPointer() const;
157 template<typename Type>
170 template<typename Type>
190 Type&
At(
const size_t index);
195 const Type&
At(
const size_t index)
const;
251 typedef typename Type* PointerType;
252 typedef typename Type ValueType;
255 typedef typename RapidVectorIterator<RapidVector>
Iterator;
582 Pose(
double x,
double y,
double z);
592 bool Equals(
const Pose& rightHandSide,
double tolerance)
const;
646 virtual const char*
const NameGet()
const = 0;
647 virtual uint32_t AxisCountGet()
const = 0;
651 virtual bool IsConfigured()
const = 0;
653 virtual const char*
const*
const ExpectedAxisNamesGet()
const = 0;
654 virtual uint32_t ExpectedAxisNamesCountGet()
const = 0;
659 virtual bool InverseKinematicsSolve(
const Pose& inputPose,
void* outputPointerSolutionVector)
const = 0;
661 virtual bool InverseKinematicsSolve(
const RobotPosition& inputPosition,
void* vpSols)
const = 0;
666 virtual void ForwardKinematicsSolve(
const double* inputJointPositions,
Pose& outputPose)
const = 0;
668 virtual void ForwardKinematicsSolve(
const double* inputJointPositions,
RobotPosition& outputPosition)
const = 0;
683 static constexpr double DefaultScaling = 1.0;
687 static constexpr double DefaultOffset = 0.0;
690 static constexpr int MaxLabelSize = 16;
691 static constexpr int ExpectedLabelBufferSize = MaxLabelSize + 1;
696 char ExpectedLabel[ExpectedLabelBufferSize];
729 class ProtectedAccessor;
731 ProtectedAccessor ProtectedAccessGet();
764 void LabelSet(const
char* const label);
768 const
char* const LabelGet() const;
771 void TransformFromKinematicOriginToRobotOriginSet(const
Pose& KinematicOriginToRobotOrigin);
774 Pose TransformFromKinematicOriginToRobotOriginGet() const;
845 ArticulatedModelBuilder();
846 ~ArticulatedModelBuilder();
970 static constexpr uint64_t TimeoutForever = 0xFFFFFFFFFFFFFFFF;
976 static constexpr uint32_t MotionFrameBufferSizeDefault = 256;
982 static constexpr uint32_t MotionFrameBufferSizeMinimum = 50;
1104 virtual void AmpEnableSet(
bool enable, int32_t ampActiveTimeoutMilliseconds) = 0;
1471 virtual bool Load(
const char*
const text) = 0;
1472 virtual bool LoadFile(
const char*
const file) = 0;
1570 virtual uint64_t
DoneWait(uint64_t timeoutMilliseconds) = 0;
void Cancel()=0
Cancel the currently running G-code program.
void ReloadLines(int32_t start=0, int32_t end=-1)=0
Reloads the lines from the last call to GcodeStringLoad() but only between start line and end of file...
uint64_t DoneWait(uint64_t timeoutMilliseconds)=0
Wait for the completion of G-code program execution with a timeout.
const char *const LineTextGet(uint32_t lineNumber)=0
Gives you the text of a specific line from the last loaded program excluding all comments and with on...
GCodeWorkOffset ActiveWorkOffsetGet()=0
Gets the enum representing the location where the current offset is saved.
void ActiveWorkOffsetSelect(GCodeWorkOffset workOffset)=0
Apply the offset saved under the specified location.
int32_t LineCountGet()=0
Get the number of lines in the last loaded G-Code program.
int32_t SyntaxErrorLineNumberGet()=0
Gets the line number of any errors in the G-Code syntax.
const char *const ProgramGet()=0
Gets the raw file contents of the last loaded program.
int32_t ExecutingLineNumberGet()=0
Get the currently executing line number.
const Pose & ActiveWorkOffsetValuesGet()=0
Gets the actual values of the currently applied offset.
LinearUnits UnitsGet()=0
Get the currently active unit as set by G20/G21.
void AccelerationRateSet(double programmingUnitsPerMinuteSquared)=0
Sets the target acceleration for the machine (units/minute^2). Should be set apprpriately based on yo...
double AccelerationRateGet()=0
Gets the target acceleration for the machine (GcodeUnitsGet()/minute^2).
void UnitsSet(LinearUnits units)=0
Set the currently active unit (same as calling G20/G21)
double DurationGet()=0
Get the time duration required to run the loaded G-Code program in seconds.
RapidVector< RobotPosition > PlannedPositionsGet(uint64_t startFrame, uint64_t frameCount)=0
Get RobotPositions representing the planned G-Code motion in cartesian space that will happen when ru...
double FeedRateGet()=0
Gets the target feed rate for the machine (GcodeUnitsGet()/minute).
void FreeAxisLetterSet(const char gcodeLetter, const int freeAxisIndex)=0
Map a letter in a Gcode file to a free axis. It will be used to specify the free axis' motion.
void WorkOffsetConfigure(GCodeWorkOffset workOffset, Vector3d offsetValues)=0
Save an XYZ offset to be used with specified G-Code work offset.
void FeedRateSet(double programmingUnitsPerMinute)=0
Sets the target feed rate for the machine (units/minute).
void Run()=0
Run the loaded G-Code file (or string). The behavior is non-blocking. Use Robot.MotionDoneWait() to b...
void Execute(GcodeCallbackData *data)
Executes the M-code callback.
Handles callbacks for M-codes within a G-code file.
Represents a G-code program executor. This class provides an interface to load and run G-code program...
void CallbackRegister(Cartesian::GcodeCallback *callback)=0
G-code callback register.
bool IsRunning()=0
Returns true if a Gcode program is executing, false otherwise.
The abstract class for Kinematic Model builders. Constructs a single Kinematic Model to use when crea...
KinematicModelBuilder(const char *const label)
The KinematicModelBuilder constructor is protected so that only derived classes can use it....
Describes the mathematical kinematic model of a robot.
const KinematicModel & ModelBuild() override
Construct the model using the information the builder currently has. The builder will maintain a refe...
LinearModelBuilder(const char *const label)
constructs a LinearModelBuilder instance.
The Builder for a linear kinematic model. Constructs a single Linear Kinematic Model to use when crea...
void JointAdd(const LinearJointMapping &joint)
adds a joint to the model using the configuration specified within the LinearJoint structure.
Pose operator*(const Pose &rightHandSide) const
Transforms rightHandSide by this. Rotates rightHandSide.position by this, adds this....
Vector3d operator*(const Vector3d &rightHandSide) const
Transforms rightHandSide by this. Rotates rightHandSide by this, and adds this.position to it.
Pose Inverse() const
Returns an inverted copy of this. this * this.inverse() = I.
Pose(const Pose &pose)
Constructor from an existing Pose.
Pose(const Quaternion &quaternion)
Constructor.
Pose Rotate(const Pose &rightHandSide) const
Rotates rightHandSide by the rotation component of this (ONLY the rotation component)
bool Equals(const Pose &rightHandSide, double tolerance) const
Approximate equality check. Checks whether all components are within the tolerance of each other.
Pose(const Vector3d position, const Quaternion &quaternion)
Constructor.
Pose(const Vector3d &position)
Constructor from an existing position Vector3d.
Pose(double x, double y, double z)
Constructor from X,Y,Z with an identity "no rotation" default Quaternion.
Vector3d Position
The position component of the Pose.
Quaternion Orientation
The orientation component of the Pose.
Pose()
Default constructor. Vector(0,0,0) Quaterion(1,0,0,0)
Vector3d operator*(const Vector3d &rightHandSide) const
Multiplication (vector rotation) operator. Rotates vector by this.
Quaternion & operator-=(const Quaternion &rightHandSide)
Subtraction assignment. Subtracts other from this. See operator-.
Quaternion & operator+=(const Quaternion &rightHandSide)
Addition assignment. Adds rightHandSide into this. See operator+.
Quaternion & Set(double w, const Vector3d &vec)
Assigns other into this.
Quaternion operator+(const Quaternion &rightHandSide) const
Adds two quaternions together. this.w + rightHandSide.w, this.v+rightHandSide.v.
Quaternion & operator=(const Quaternion &rightHandSide)
Assignment operator. Copies underlying.
Quaternion(double x, double y, double z)
Euler constructor.
Quaternion & operator*=(double s)
Multiplication (scalar) assignment operator. See operator*(double)
Quaternion Conjugate() const
Negates the imaginary component of the Quaternion.
Quaternion Inverse() const
Conjugate scaled by 1 / SumSquares()
Quaternion operator-(const Quaternion &rightHandSide) const
Subtraction operator. this.w - rightHandSide.w, this.v-rightHandSide.v.
Quaternion operator-() const
Negates this quaternion (w, and v)
Quaternion Normalized() const
Retunrs a normalized copy of this.
void ToAngleAxis(double &outAngle, Vector3d &outAxis) const
Gets the axis angle representation of this quaternion.
Quaternion & Set(const Quaternion &otherQuaternion)
Assigns other into this.
Quaternion & Set(double x, double y, double z)
Assigns the quaternion defined by the Euler angles into this. If you get unexpected values,...
bool operator==(const Quaternion &rightHandSide) const
Exact equality check. See equals for approximately equal to.
double Magnitude() const
Gets the magnitude of this. sqrt(SumSquares())
Vector3d ToEuler() const
Gets the Euler Angle representation of this quaternion.
Quaternion operator*(double s) const
Multiplication (scalar) operator. w*s, v*s.
static Quaternion FromAngleAxis(double angle, const Vector3d &axis)
Creates a quaternion from an axis angle representation.
Quaternion operator*(const Quaternion &rightHandSide) const
Multiplication (rotation) operator. Rotates other by this.
Quaternion(double w, const Vector3d &v)
Constructor.
bool operator!=(const Quaternion &rightHandSide) const
Exact inequality check. See equals for approximately equal to.
Quaternion(const Vector3d &rpy)
Euler Constructor (Alternate)
Quaternion & Normalize()
Normalizes this. Scales each component by 1 / magnitude.
Quaternion(const Quaternion &otherQuaternion)
Constructor.
double SumSquares() const
Gets the sum of the components squared (w*w+this.dot(this))
Quaternion(double w, double x, double y, double z)
Constructor.
double Dot(const Quaternion &rightHandSide) const
Returns the dot product of each element. w*rightHandSide.w+v.dot(rightHandSide.v)
Quaternion & Set(double w, double x, double y, double z)
Assigns each component into this.
Quaternion & Set(const Vector3d &vec)
Assigns the quaternion defined by the Euler Angles into this.
bool Equals(const Quaternion &rightHandSide, const double tolerance) const
Equality check within tolerance.
void ToMatrix(double *matrix) const
Quaternion To Matrix.
static Quaternion FromMatrix(const double *const matrix)
Matrix to Quaternion.
Quaternion for representing rotations.
double W
W (real component) of Quaternion. Do not modify this unless you know what you are doing.
Quaternion()
Default Constructor. W=1, X=Y=Z=0.
Vector3d V
Vector3d (imaginary) component of Quaternion. 1->x, 2->y, 3->z. Do not modify this unless you know wh...
const size_t Size() const
Returns the number of elements in the vector.
const Type & operator[](const size_t index) const
Returns a const reference to the element at the location specified by the index.
const Type & Back() const
Returns a const reference to the last element in the vector.
Iterator begin() noexcept
Returns a RapidVectorIterator to the first element of the vector. The naming convention follows STL c...
Type & Front()
Returns a reference to the first element in the vector.
const Type & Front() const
Returns a const reference to the first element in the vector.
const Type & At(const size_t index) const
Returns a const reference to the element at the location specified by the index.
void PushBack(const Type &element)
Appends the given element to the end of the vector.
Type & Back()
Returns a reference to the last element in the vector.
Type & operator[](const size_t index)
Returns a reference to the element at the location specified by the index.
Type & At(const size_t index)
Returns a reference to the element at the location specified by the index.
A wrapper class for the C++ STL vector class that aims to maintain application binary interface....
RapidVector(RapidVector &&other) noexcept
Move constructor. Replaces contents with those of the other RapidVector.
RapidVectorIterator< RapidVector > Iterator
The iterator type for this RapidVector.
~RapidVector()
Destructs the vector and deallocates used storage.
RapidVector & operator=(const RapidVector &other)
Copy assignment operator. Replaces contents with the contents of the other RapidVector.
RapidVector(const RapidVector &other)
Copy constructor. Constructs a RapidVector as a deep-copy.
RapidVector(RapidVectorImplementation< Type > *)
Constructs a RapidVector with the given implementation. Intended for RSI internal use only.
void Clear()
Erases all elements from the vector.
void PopBack()
Removes the last element from the container. Calling PopBack() on an empty container results in undef...
RapidVector(const size_t size)
Constructs a vector with the specified size.
RapidVector & operator=(RapidVector &&other) noexcept
Move assignment operator. Replaces contents with those of the other RapidVector. The original content...
RapidVector()
Default constructor that constructs an empty vector.
Forward declaration of the implementation class for RapidVector.
RapidVector< double > JointsActualPositionsGet()=0
Get the actual positions of the axes in the underlying MultiAxis.
const Pose & EndEffectorTransformGet()=0
End of Robot to TCP.
bool MotionDoneGet()=0
Check to see if motion is done and settled.
double PathAccelerationGet()=0
Gets the target acceleration for the machine (UserUnits/second^2).
bool PathStateWait(PathState stateWaitFor, uint64_t timeoutMilliseconds)=0
Waits for a specific path state.
void OriginTransformSet(const Pose &transform)=0
Transform that defines the origin of the robot in the world. For example if you have a gantry that is...
bool PathStateWaitChange(PathState stateWaitChange, uint64_t timeoutMilliseconds)=0
Waits for the path state to not be the specified state.
RobotPosition ActualPositionGet()=0
Get the current actual position of the robot from the trajectory executor, in the Robot model's units...
void PathArc(const RobotPosition &target, double radius, RotationDirection direction)=0
Appends an arc on to the current on the PathPlaneGet() plane XY by default.
uint64_t MotionDoneWait()=0
Waits for a move to complete.
void Stop()=0
Stop an axis.
Pose CommandPoseGet(LinearUnits units)=0
Get the current commanded pose of the robot from the trajectory executor in the specified units.
double PathVelocityGet()=0
Gets the target velocity for the machine (UserUnits/second).
Pose CommandPoseGet()=0
Get the current commanded pose of the robot from the trajectory executor, in the Robot model's units.
RapidVector< RobotPosition > PathPlannedPositionsGet(uint64_t startFrame, uint64_t frameCount)=0
Get Positions (see RobotPosition) representing the planned motion in cartesian space that will happen...
uint32_t MotionFrameBufferSizeGet()=0
Gets the TrajectoryExecutor's buffer size in frames, one frame is used per RMP sample period.
void PathLine(const RobotPosition &position)=0
static Robot * RobotCreate(MotionController *controller, MultiAxis *multiAxis, const char *const modelIdentifier, uint32_t motionFrameBufferSize)
void PathVelocitySet(double unitsPerSecond)=0
Sets the target linear cartesian velocity for each move (UserUnits/second).
Plane PathPlaneGet()=0
Gets the plane some arcs will be forced to be on.
const char *const ErrorMessageGet()=0
Get the text of any error in the Trajectory Executor.
RobotPosition CommandPositionGet(LinearUnits units)=0
Get the current commanded position of the robot from the trajectory executor in the specified units.
uint64_t MotionDoneWait(uint64_t timeoutMilliseconds)=0
Waits for a move to complete.
bool IsRunning()=0
Returns whether or not the robot is in motion (from executor or other source). Can be used to determi...
void Abort()=0
Abort an axis.
bool HasError()=0
Get the error state of the underlying Trajectory Executor.
double PathProcessLoadedMoves()=0
Processes our loaded moves. Used internally and to check whether loaded moves are valid,...
void EndEffectorTransformSet(const Pose &transform)=0
Transform that defines the control point relative to the end end of the current kinematic model For e...
bool MotionCounterWait(uint64_t motionWaitFor, uint64_t timeoutMilliseconds)=0
Waits for the counter to be greater than or equal to the specified state.
RobotPosition ActualPositionGet(LinearUnits units)=0
Get the current actual position of the robot from the trajectory executor in the specified units.
void PathPlaneSet(Plane plane)=0
Sets the plane for the purposes of ambiguous cases (arcs >= 180deg). Last set plane or XY plane is de...
const Pose & OriginTransformGet()=0
Offset for the origin location.
double PathLinearScalingGet() const =0
Gets scaling between input to path motion and output of path motion to the kinematic model.
RapidVector< double > InverseKinematics(Pose pose)=0
Run the given pose through the current inverse kinematic model to see the joint positions the robot w...
Pose ActualPoseGet(LinearUnits units)=0
Get the current actual pose of the robot from the trajectory executor in the specified units.
PathMode PathProgrammingModeGet()=0
Gets the programming mode (Relative/Absolute).
static Robot * RobotCreate(MotionController *controller, MultiAxis *multiAxis, const char *const modelIdentifier)
RobotPosition ForwardKinematicsPosition(const RapidVector< double > &joints)=0
Get the Actual position of the robot from the the joint MultiAxis positions.
void PathLinearScalingSet(double scaleFactor)=0
Sets scaling between the input to path motion and output of path motion to the kinematic model.
static Robot * RobotCreate(MotionController *controller, MultiAxis *multiAxis, KinematicModelBuilder *builder, uint32_t motionFrameBufferSize)
Create a Robot object to use G-Code, path motion, etc.
void AmpEnableSet(bool enable, int32_t ampActiveTimeoutMilliseconds)=0
Enable all amplifiers.
void EStopAbort()=0
E-Stop, then abort an axis.
void PathAccelerationSet(double unitsPerSecondSquared)=0
Sets the target acceleration for the machine (UserUnits/second^2). Should be set appropriately based ...
LinearUnits PathUnitsGet() const =0
Gets the units of path motion.
bool PathIsRunning()=0
Returns whether or not a planned path is being executed. All G-Code gets converted to path....
void PathArc(const Pose &target, double radius, RotationDirection direction)=0
Appends an arc on to the current on the PathPlaneGet() plane XY by default.
RobotPosition CommandPositionGet()=0
Get the current commanded position of the robot from the trajectory executor, in the Robot model's un...
Pose ActualPoseGet()=0
Get the current actual pose of the robot from the trajectory executor, in the Robot model's units.
void PathUnitsSet(LinearUnits units)=0
Defines the units Cartesian Path Motion is in.
void PathLine(const Pose &target)=0
void MoveAbsolute(const Pose &absolutePose)=0
Executes a point-to-point absolute motion in cartesian space.
PathState PathStateGet()=0
Gets the path state of the Robot.
void EStop()=0
Commands a joint EStop and clears the loaded moves.
void MoveRelative(const Pose &relativePose)=0
Executes a point-to-point motion relative to the current end effector Pose.
RapidVector< double > JointsCommandPositionsGet()=0
Get the commanded positions of the axes in the underlying MultiAxis.
Pose ForwardKinematics(const RapidVector< double > &joints)=0
Get the Actual pose of the robot from the the joint MultiAxis positions.
void PathProgrammingModeSet(PathMode mode)=0
Sets the programming mode (Relative/Absolute).
void PathArc(const Pose &target, const Vector3d ¢er, RotationDirection direction)=0
Appends an arc on to the current path with end pose about a specific center point.
uint64_t MotionCounterGet()=0
Gets the current motion counter of the Robot.
const double ScaleFactorBetweenUnitsGet(LinearUnits from, LinearUnits to)=0
Gets scaling for scale factor needed to convert from -> to units by multiplying
bool MotionCounterWaitChange(uint64_t motionWaitChange, uint64_t timeoutMilliseconds)=0
Waits for the state to change off the specified counter value.
void PathArc(const RobotPosition &RobotPosition, const Vector3d ¢er, RotationDirection direction)=0
Appends an arc on to the current path with end pose about a specific center point.
double PathDurationGet()=0
Get total (seconds) duration of the planned motion that will happen when run is called.
void Resume()=0
Resume an axis.
RapidVector< double > InverseKinematics(RobotPosition pose)=0
Run the given pose through the current inverse kinematic model to see the joint positions the robot w...
void Run()=0
Run the loaded path lines/arcs. The behavior is non-blocking. Use Robot.MotionDoneWait() to block.
Represents a collection of joints in Cartesian space with forward and inverse kinematics....
void ClearFaults()=0
Clears the MultiAxis fault then the Robot's error bit.
const KinematicModel & ModelGet()=0
Get the model this robot was created with Visit our Topic Page for more information.
void PathClear()=0
Clears out all loaded lines and arcs from the path. Part of the PathMotion method group....
static void RobotDelete(MotionController *controller, Robot *robot)
Delete a Robot.
RSI::RapidCode::Cartesian::Gcode * Gcode
An object to load and run Gcode files.
A representation of the robot containing the Pose and the positions of the free axes.
RobotPosition(const Cartesian::Pose &newPose, const RapidVector< double > &freeAxes)
Copies the new pose into this->Pose. Makes a deep copy of the given RapidVector for this->FreeAxes.
RobotPosition()
Default constructor. Initializes all values to 0. Leaves the FreeAxes RapidVector empty.
Cartesian::RobotPosition operator*(const Cartesian::RobotPosition &otherPosition) const
multiplies this->Pose by otherPosition.Pose and adds otherPosition.FreeAxes to this->FreeAxes (since ...
Pose Pose
The Robot's Pose.
double AxisValueGet(uint32_t index) const
Gets the freeAxis value at the specified index. Returns 0 if index is out of bounds of the FreeAxes.
RobotPosition(const Cartesian::Pose &newPose, const size_t numberOfFreeAxes=0)
Copies the new pose into this->Pose. Specified number of free axes initialized with zeroes for their ...
void AxisValueSet(uint32_t index, double value)
Sets the freeaxis value at specified index to the passed value. Does nothing if index is out of bound...
RobotPosition(const Cartesian::RobotPosition &otherPosition)
Copy constructor. Copies values of Pose and FreeAxes.
RapidVector< double > FreeAxes
The Robot's free axes. Will have elements added to it for each free axis in the robot.
Cartesian::RobotPosition operator*(const Cartesian::Pose &otherPose) const
multiplies this->Pose by pose. Does not modify this->FreeAxes.
Vector3d is used for three-dimensional points and vectors.
double Z
The Z coordinate.
double X
The X coordinate.
Vector3d Normal() const
Returns a normalized copy of this.
Vector3d operator*(double scalar) const
Returns a Vector3d scaled scaled by. X*scalar, Y*scalar, Z*scalar.
Vector3d & Set(double x, double y, double z)
Sets X=x, Y=y, Z=z.
Vector3d operator+(const Vector3d &rightHandSide) const
Returns a copy of rightHandSide added to this. this.X+rightHandSide.X, this.Y+rightHandSide....
Vector3d operator/(double scalar) const
Returns a Vector3d scaled scaled by. X/scalar, Y/scalar, Z/scalar.
Vector3d & Set(const Vector3d &rightHandSide)
Sets X=rightHandSide.X, Y=rightHandSide.Y, Z=rightHandSide.Z.
Vector3d operator-(const Vector3d &rightHandSide) const
Returns a copy of rightHandSide subtracted from this. this.X-rightHandSide.X, this....
Vector3d & operator*=(double scalar)
Scales each element by scalar. X*=scalar, Y*=scalar, Z*=scalar.
Vector3d operator-() const
Returns a copy of this with elements negated. -X, -Y, -Z.
double Length() const
Returns the length of the vector. Aka the magnitude =sqrt(SumSquares)
bool operator!=(const Vector3d &rightHandSide) const
Returns whether this is not exactly equal to rightHandSide.
bool operator==(const Vector3d &rightHandSide) const
Returns whether this is exactly equal to rightHandSide.
Vector3d & operator/=(double scalar)
Scales each element by scalar. X/=scalar, Y/=scalar, Z/=scalar.
double SumSquares() const
Returns the sum of squares. X*X+Y*Y+Z*Z.
Vector3d()
Default constructor. X=Y=Z=0.
Vector3d & operator-=(const Vector3d &rightHandSide)
Subtracts rightHandSide from this. this.X-=rightHandSide.X, this.Y-=rightHandSide....
double Y
The Y coordinate.
Vector3d & operator+=(const Vector3d &rightHandSide)
Adds rightHandSide to this. this.X+=rightHandSide.X, this.Y+=rightHandSide.Y, this....
double Dot(const Vector3d &rightHandSide) const
Dot Product. this.X*rightHandSide.X + this.Y*rightHandSide.Y + this.Z*rightHandSide....
Vector3d Inverse() const
Returns an inverted copy of this. this * this.inverse() = I.
Vector3d Cross(const Vector3d &rightHandSide) const
Cross Product. Vector.X = this.Y*rightHandSide.z - this.Z*rightHandSide.Y Vector.Y = this....
Vector3d & operator=(const Vector3d &rightHandSide)
Sets this = rightHandSide.
Vector3d(double x, double y, double z)
Constructor. X=x, Y=y, Z=z.
bool Equals(const Vector3d &rightHandSide, const double tolerance) const
Checks whether this.X==rightHandSide.X && this.Y==rightHandSide.Y && this.Z==rightHandSide....
Vector3d & Normalize()
Normalizes this.
Vector3d(const Vector3d &rightHandSide)
Constructor. X=rightHandSide.X, Y=rightHandSide.Y, Z=rightHandSide.Z.
Represents the RMP soft motion controller. This class provides an interface to general controller con...
Represents multiple axes of motion control, allows you to map two or more Axis objects together for e...
The RapidCode base class. All non-error objects are derived from this class.
Represents the error details thrown as an exception by all RapidCode classes. This class contains an ...
PathMode
Motion types. For G-code use and Cartesian path motion.
Plane
Rotational directions about and axis.
CartesianAxis
This enum specifies which Cartesian axis a LinearJointMapping maps a robot joint to.
PathState
State of the Robot.
@ Stopping
Motion was interrupted by a stop command or error on the MultiAxis. EStop time will be used....
@ Moving
A path motion is in progress.
@ Idle
The path motion is not moving or in progress. If the joints are moved directly, the PathState will be...
@ Uninitialized
Library is loading. Wait until it is idle.
RotationDirection
Rotational directions about an axis.
LinearUnits
Unit types. For G-code use.
GCodeWorkOffset
Register names for G-Code work offsets.
const char * LineText
The actual line content from the G-code file.
RsiError * UserError
Allows the user to set give error details to the G-Code execution thread what occurred during the exe...
int32_t LineNumber
The line number in the G-code file where the M-code is encountered.
Holds data for the G-code M-code callback mechanism.
CartesianAxis CartesianCoordinate
Data for adding joint or free-axis mappings when building a kinematic model.
double Offset
The offset value that will be added to the scaled joint position.
int JointIndex
The index of the robot's joint to map (within an array of joint positions). Often this index will ref...
ModelAxisMapping(int jointIndex)
Constructor that sets the FointIndex and uses defaults for the rest of the data members.
double Scaling
The scaling value that the joint position will be multiplied by.
ModelAxisMapping(int jointIndex, double scaling, double offset, const char *const label)
Constructor that sets all data members in the struct.