APIs, concepts, guides, and more
cartesianrobot.h
1#pragma once
2#ifndef _CARTESIANROBOT_H
3#define _CARTESIANROBOT_H
4
5#include "rsi.h" // HAS_CARTESIAN_ROBOT defined in rsi.h
6#if defined(HAS_CARTESIAN_ROBOT)
7#include <cmath>
8
9
10// doxygen requires these stacked namespaces, you CANNOT use RSI::RapidCode::Cartesian {
11namespace RSI
12{
13namespace RapidCode
14{
15
17namespace Cartesian
18{
21
23 enum class PathState
24 {
26 Idle,
27 Moving,
28 Stopping,
29 };
30
31 constexpr double pi = 3.1415926535897932384626433832795028841971693993751;
32
34 enum class PathMode
35 {
36 Absolute,
37 Relative,
38 };
39
42 {
43 Clockwise,
45 };
46
48 enum class Plane
49 {
50 None,
51 XY,
52 XZ,
53 YZ,
54 };
55
57 enum class GCodeWorkOffset {
58 Machine = 0,
59 G54 = 54,
60 G55 = 55,
61 G56 = 56,
62 G57 = 57,
63 G58 = 58,
64 G59 = 59,
65 };
66
68 enum class LinearUnits
69 {
70 None,
72 Inches,
73 Feet,
75 Meters,
76 };
77
79 enum class RotationalUnits
80 {
81 None,
82 Degrees,
83 Radians,
85 };
86
95 enum class CartesianAxis
96 {
97 X = 0,
98 Y = 1,
99 Z = 2,
100 Roll = 3,
101 Pitch = 4,
102 Yaw = 5,
103 };
104
106
107 class Gcode; // forward declaration
108
109 template<typename ContainerClass>
110 class RSI_API RapidVectorIterator
111 {
112 public:
114 typedef typename ContainerClass::ValueType ValueType;
115
117 typedef typename ContainerClass::PointerType PointerType;
118
121 ValueType& operator*();
122
125 const ValueType& operator*() const;
126
129 RapidVectorIterator& operator++();
130
133 RapidVectorIterator operator++(int);
134
137 bool operator==(const RapidVectorIterator&) const;
138
141 bool operator!=(const RapidVectorIterator&) const;
142
144 RapidVectorIterator(PointerType pointerArgument, PointerType startArgument, const size_t containerSize);
145
147 RapidVectorIterator(const RapidVectorIterator&) = default;
148
150 RapidVectorIterator& operator=(const RapidVectorIterator&) = default;
151
153 RapidVectorIterator(RapidVectorIterator&&) noexcept = default;
154
156 RapidVectorIterator& operator=(RapidVectorIterator&&) noexcept = default;
157 private:
158 PointerType pointer;
159 PointerType start, end;
160 void VerifyPointer() const;
161 };
162
164 template<typename Type>
166
169
177 template<typename Type>
178 class RSI_API RapidVector
179 {
180 private:
181 // The pointer to the implementation.
183 public:
187 Type& operator[](const size_t index);
188
192 const Type& operator[](const size_t index) const;
193
197 Type& At(const size_t index);
198
202 const Type& At(const size_t index) const;
203
206 void PushBack(const Type& element);
207
210 const size_t Size() const;
211
213 void Clear();
214
216 void PopBack();
217
220 Type& Front();
221
224 const Type& Front() const;
225
228 Type& Back();
229
232 const Type& Back() const;
233
236
238 RapidVector(const size_t size);
239
242
245
248
251
253 RapidVector(RapidVector&& other) noexcept;
254
257
258 typedef typename Type* PointerType;
259 typedef typename Type ValueType;
260
262 typedef typename RapidVectorIterator<RapidVector> Iterator;
263
266 Iterator begin() noexcept;
267
270 Iterator begin() const noexcept;
271
275 Iterator end() const noexcept;
276 };
277
279 class RSI_API Vector3d
280 {
281 public:
283 double X;
284
286 double Y;
287
289 double Z;
290
293
295 Vector3d(double x, double y, double z);
296
298 Vector3d(const Vector3d& rightHandSide);
299
301 double Dot(const Vector3d& rightHandSide) const;
302
307 Vector3d Cross(const Vector3d& rightHandSide) const;
308
310 Vector3d& Set(double x, double y, double z);
311
313 Vector3d& Set(const Vector3d& rightHandSide);
314
317 bool Equals(const Vector3d& rightHandSide, const double tolerance) const;
318
320 double SumSquares() const;
321
323 double Length() const;
324
327
330
332 Vector3d& operator=(const Vector3d& rightHandSide);
334 bool operator==(const Vector3d& rightHandSide) const;
336 bool operator!=(const Vector3d& rightHandSide) const;
338 Vector3d operator*(double scalar) const;
340 Vector3d& operator*=(double scalar);
342 Vector3d operator+(const Vector3d& rightHandSide) const;
344 Vector3d& operator+=(const Vector3d& rightHandSide);
346 Vector3d operator-(const Vector3d& rightHandSide) const;
350 Vector3d& operator-=(const Vector3d& rightHandSide);
352 Vector3d operator/(double scalar) const;
354 Vector3d& operator/=(double scalar);
357 };
358
360 class RSI_API Quaternion
361 {
362 public:
365
367 double W;
368
371
377 Quaternion(double w, double x, double y, double z);
378
381 Quaternion(const Quaternion& otherQuaternion);
382
386 Quaternion(double w, const Vector3d& v);
387
392 Quaternion(double x, double y, double z);
393
397 Quaternion(const Vector3d& rpy, RotationalUnits units = RotationalUnits::Radians);
398
402 bool operator==(const Quaternion& rightHandSide) const;
403
407 bool operator!=(const Quaternion& rightHandSide) const;
408
412 Quaternion& operator=(const Quaternion& rightHandSide);
413
417 Quaternion operator+(const Quaternion& rightHandSide) const;
418
422 Quaternion& operator+=(const Quaternion& rightHandSide);
423
427 Quaternion operator-(const Quaternion& rightHandSide) const;
428
432 Quaternion& operator-=(const Quaternion& rightHandSide);
433
437 Quaternion operator*(const Quaternion& rightHandSide) const;
438
442 Quaternion operator*(double s) const;
443
448
452 Vector3d operator*(const Vector3d& rightHandSide) const;
453
457
461 double Dot(const Quaternion& rightHandSide) const;
462
466 Quaternion& Set(const Quaternion& otherQuaternion);
467
474 Quaternion& Set(double w, double x, double y, double z);
475
480 Quaternion& Set(double w, const Vector3d& vec);
481
489 Quaternion& Set(double x, double y, double z);
490
495 Quaternion& Set(const Vector3d& vec, RotationalUnits units = RotationalUnits::Radians);
496
501 bool Equals(const Quaternion& rightHandSide, const double tolerance) const;
502
507 bool EqualsOrientation(const Quaternion& rightHandSide, const double tolerance) const;
508
512
516
517
520 double SumSquares() const;
521
524 double Magnitude() const;
525
529
533
534
535
540 static Quaternion FromAngleAxis(double angle, const Vector3d& axis);
541
545 void ToAngleAxis(double& outAngle, Vector3d& outAxis) const;
546
550 Vector3d ToEuler(RotationalUnits units = RotationalUnits::Radians) const;
551
558 static Quaternion FromMatrix(const double* const matrix);
559
560
566 void ToMatrix(double* matrix) const;
567 };
568
570 class RSI_API Pose {
571 public:
574
577
580
583 Pose(const Pose& pose);
584
588 Pose(const Vector3d position, const Quaternion& quaternion);
589
592 Pose(const Vector3d& position);
593
598 Pose(double x, double y, double z);
599
602 Pose(const Quaternion& quaternion);
603
608 bool Equals(const Pose& rightHandSide, double tolerance) const;
609
615 bool EqualsOrientation(const Pose& rightHandSide, double tolerance) const;
616
620 Pose Rotate(const Pose& rightHandSide) const;
621
625 Vector3d operator*(const Vector3d& rightHandSide) const;
626
630 Pose operator*(const Pose& rightHandSide) const;
631
634 Pose Inverse() const;
635 };
636
638 class RSI_API RobotPosition
639 {
640 public:
643
646
652 RobotPosition(const Cartesian::Pose& newPose, const size_t numberOfFreeAxes = 0);
654 RobotPosition(const Cartesian::Pose& newPose, const RapidVector<double>& freeAxes);
660 void AxisValueSet(uint32_t index, double value);
662 double AxisValueGet(uint32_t index) const;
665 };
666
668 class RSI_API KinematicModel
669 {
670 public:
671 virtual const char* const NameGet() const = 0;
672 virtual uint32_t AxisCountGet() const = 0;
673
674 virtual LinearUnits UnitsGet() const = 0;
675 virtual RotationalUnits RotationalUnitsGet() const = 0;
676
677 virtual bool IsConfigured() const = 0;
678
679 virtual const char* const* const ExpectedAxisNamesGet() const = 0;
680 virtual uint32_t ExpectedAxisNamesCountGet() const = 0;
681
682 virtual uint32_t FreeAxisCountGet() const = 0;
683
684 // input function
685 // inputPose requires this to be in robot centric coordinates.
686 // remove tool offset and robot base offset
687 virtual bool InverseKinematicsSolve(const Pose& inputPose, void* outputPointerSolutionVector) const = 0;
688
689 virtual bool InverseKinematicsSolve(const RobotPosition& inputPosition, void* vpSols) const = 0;
690
691 // ouput function
692 // inputJointPositions requires this to be in robot centric coordinates.
693 // apply tool offset and robot base offset
694 virtual void ForwardKinematicsSolve(const double* inputJointPositions, Pose& outputPose) const = 0;
695
696 virtual void ForwardKinematicsSolve(const double* inputJointPositions, RobotPosition& outputPosition) const = 0;
697
698 virtual bool IsArticulated() const = 0;
699 };
700
702 struct RSI_API ModelAxisMapping
703 {
704
705 public:
709
711 double Scaling;
712 static constexpr double DefaultScaling = 1.0;
713
715 double Offset;
716 static constexpr double DefaultOffset = 0.0;
717
719 static constexpr int MaxLabelSize = 16;
720 static constexpr int ExpectedLabelBufferSize = MaxLabelSize + 1;
721
725 char ExpectedLabel[ExpectedLabelBufferSize];
726
728 ModelAxisMapping(int jointIndex);
729
731 ModelAxisMapping(int jointIndex, double scaling, double offset, const char* const label);
732
733 // ModelAxisMapping Destructor.
734 virtual ~ModelAxisMapping() = default;
735 };
736
742 {
743 protected:
744 // Stores implementation details for the KinematicModelBuilder. (Pointer to implementation pattern)
745 struct Storage;
746 Storage* storage;
747
750 KinematicModelBuilder(Storage* storage);
751
752 // Protect the copy constructor, for internal use only.
754
755 public:
756 virtual ~KinematicModelBuilder();
757
758 // Delete the copy-assignment constructor.
759 KinematicModelBuilder& operator=(const KinematicModelBuilder&) = delete;
760
761 // Move constructors
763 KinematicModelBuilder& operator=(KinematicModelBuilder&&) noexcept;
764
769 virtual const KinematicModel& ModelBuild() = 0;
770
774 const KinematicModel& ModelGet();
775
778 void UnitsSet(LinearUnits units);
779
782 LinearUnits UnitsGet() const;
783
786 void RotationalUnitsSet(RotationalUnits units);
787
790 RotationalUnits RotationalUnitsGet() const;
791
794 void LabelSet(const char* const label);
795
798 const char* const LabelGet() const;
799
801 void TransformFromKinematicOriginToRobotOriginSet(const Pose& KinematicOriginToRobotOrigin);
802
804 Pose TransformFromKinematicOriginToRobotOriginGet() const;
805
808 void FreeAxisAdd(const ModelAxisMapping& freeAxis);
809 };
810
825 struct RSI_API LinearJointMapping : public ModelAxisMapping
826 {
827 public:
831
832 LinearJointMapping(int jointIndex, CartesianAxis cartesianCoordinate);
833 LinearJointMapping(int jointIndex, CartesianAxis cartesianCoordinate, double scaling, double offset, const char* const label);
834 };
835
839 {
840 // Stores implementation details for the LinearModelBuilder. (Pointer to implementation pattern)
841 struct Storage;
842 Storage* storage;
843
844 public:
845
850 const KinematicModel& ModelBuild() override;
851
853 void JointAdd(const LinearJointMapping& joint);
854
857 LinearModelBuilder(const char* const label);
859
860 // Move constructors
861 LinearModelBuilder(LinearModelBuilder&& other) noexcept;
862 LinearModelBuilder& operator=(LinearModelBuilder&&) noexcept;
863
864 // Disable copy constructors
865 LinearModelBuilder(const LinearModelBuilder&) = delete;
866 LinearModelBuilder& operator=(const LinearModelBuilder&) = delete;
867 };
868
869 // UNSUPPORTED
870 class RSI_API ArticulatedModelBuilder : public KinematicModelBuilder
871 {
872 // Stores implementation details for the ArticulatedModelBuilder. (Pointer to implementation pattern)
873 struct Storage;
874 Storage* storage;
875
876 public:
877 const KinematicModel& ModelBuild() override;
878 ArticulatedModelBuilder();
879 ~ArticulatedModelBuilder();
880 };
881
900 int32_t LineNumber;
901
906 const char* LineText;
907
917 };
918
931 class RSI_API GcodeCallback
932 {
933 public:
946 virtual void Execute(GcodeCallbackData* data) {};
947
948 virtual ~GcodeCallback() = default; // Virtual destructor for C++ base classes
949 };
950
955 class RSI_API Robot : public virtual RapidCodeObject
956 {
957 public:
958
963
977 static Robot* RobotCreate(MotionController* controller, MultiAxis* multiAxis, KinematicModelBuilder* builder, uint32_t motionFrameBufferSize);
978
983 static Robot* RobotCreate(MotionController* controller, MultiAxis* multiAxis, const char* const modelIdentifier);
984
989 static Robot* RobotCreate(MotionController* controller, MultiAxis* multiAxis, const char* const modelIdentifier, uint32_t motionFrameBufferSize);
990
992 static void RobotDelete(MotionController* controller, Robot* robot);
993
995
996
1001
1003 static constexpr uint64_t TimeoutForever = 0xFFFFFFFFFFFFFFFF;
1004
1009 static constexpr uint32_t MotionFrameBufferSizeDefault = 256;
1010
1015 static constexpr uint32_t MotionFrameBufferSizeMinimum = 50;
1017
1018
1023
1029
1034 virtual bool PathStateWait(PathState stateWaitFor, uint64_t timeoutMilliseconds) = 0;
1035
1040 virtual bool PathStateWaitChange(PathState stateWaitChange, uint64_t timeoutMilliseconds) = 0;
1041
1042
1047 virtual uint64_t MotionCounterGet() = 0;
1048
1053 virtual void MotionCounterWait(uint64_t motionCount, uint64_t timeoutMilliseconds) = 0;
1054
1056 virtual uint64_t SampleCounterGet() = 0;
1057
1062 virtual void SampleCounterWait(uint64_t sampleCount, uint64_t timeoutMilliseconds) = 0;
1063
1067 virtual bool IsRunning() = 0;
1068
1072 virtual bool PathIsRunning() = 0;
1073
1080 virtual bool MotionDoneGet() = 0;
1081
1088 virtual uint64_t MotionDoneWait() = 0;
1089
1097 virtual uint64_t MotionDoneWait(uint64_t timeoutMilliseconds) = 0;
1098
1104 virtual bool HasError() = 0;
1105
1110 virtual const char* const ErrorMessageGet() = 0;
1111
1113
1114
1118
1121 virtual void Resume() = 0;
1122
1125 virtual void Stop() = 0;
1126
1129 virtual void EStopAbort() = 0;
1130
1133 virtual void Abort() = 0;
1134
1138 virtual void AmpEnableSet(bool enable, int32_t ampActiveTimeoutMilliseconds) = 0;
1139
1146 virtual void EStop() = 0;
1147
1149 virtual void ClearFaults() = 0;
1150
1151
1152
1156
1166 virtual Pose ActualPoseGet(LinearUnits units = LinearUnits::None) = 0;
1167
1177 virtual RobotPosition ActualPositionGet(LinearUnits units = LinearUnits::None) = 0;
1178
1187 virtual Pose CommandPoseGet(LinearUnits units = LinearUnits::None) = 0;
1188
1197 virtual RobotPosition CommandPositionGet(LinearUnits units = LinearUnits::None) = 0;
1198
1204
1210
1216
1222
1228 virtual Pose ForwardKinematics(const RapidVector<double>& joints) = 0;
1229
1236
1240
1242 virtual const KinematicModel& ModelGet() = 0;
1243
1247 virtual void EndEffectorTransformSet(const Pose& transform) = 0;
1248
1250 virtual void EndEffectorTransformSet(const RobotPosition& transformPosition) = 0;
1251
1255 virtual void OriginTransformSet(const Pose& transform) = 0;
1257 virtual void OriginTransformSet(const RobotPosition& transformPosition) = 0;
1258
1262
1265 virtual const RobotPosition& OriginTransformGet() = 0;
1266
1271 virtual const double ScaleFactorBetweenUnitsGet(LinearUnits from, LinearUnits to) = 0;
1272
1278
1282
1291 virtual void MoveAbsolute(const Pose& absolutePose) = 0;
1292
1293
1303 virtual void MoveRelative(const Pose& relativePose) = 0;
1304
1305
1310
1314 virtual void PathClear() = 0;
1315
1321 virtual void PathVelocitySet(double unitsPerSecond) = 0;
1322
1328 virtual double PathVelocityGet() = 0;
1329
1334 virtual void PathAccelerationSet(double unitsPerSecondSquared) = 0;
1335
1339
1341 virtual double PathAccelerationGet() = 0;
1342
1349 virtual void PathProgrammingModeSet(PathMode mode) = 0;
1350
1357
1364 virtual void PathArc(const Pose& target, double radius, RotationDirection direction) = 0;
1365
1372 virtual void PathArc(const RobotPosition& target, double radius, RotationDirection direction) = 0;
1373
1378 virtual void PathArc(const Pose& target, const Vector3d& center, RotationDirection direction) = 0;
1379
1384 virtual void PathArc(const RobotPosition& RobotPosition, const Vector3d& center, RotationDirection direction) = 0;
1385
1386
1387 // @brief Appends a line on the current path
1391 virtual void PathLine(const Pose& target) = 0;
1392
1393 // @brief Appends a line on the current path
1397 virtual void PathLine(const RobotPosition& position) = 0;
1398
1402 virtual void PathPlaneSet(Plane plane) = 0;
1403
1407 virtual Plane PathPlaneGet() = 0;
1408
1414 virtual void PathLinearScalingSet(double scaleFactor) = 0;
1415
1422 virtual double PathLinearScalingGet()const = 0;
1423
1428 virtual void PathUnitsSet(LinearUnits units) = 0;
1429
1433 virtual LinearUnits PathUnitsGet()const = 0;
1434
1438 virtual double PathProcessLoadedMoves() = 0;
1439
1450 virtual RapidVector<RobotPosition> PathPlannedPositionsGet(uint64_t startFrame, uint64_t frameCount) = 0;
1451
1456 virtual double PathDurationGet() = 0;
1457
1463 virtual void Run() = 0;
1464
1481 virtual uint32_t MotionFrameBufferSizeGet()=0;
1482
1484
1487
1488 };
1489
1493 class RSI_API Gcode : public virtual RapidCodeObject
1494 {
1496 public:
1501
1506 virtual void FeedRateSet(double programmingUnitsPerMinute) = 0;
1507
1513 virtual void AccelerationRateSet(double programmingUnitsPerMinuteSquared) = 0;
1514
1522
1526 virtual void Load(const char* const text) = 0;
1527
1531 virtual void LoadFile(const char* const file) = 0;
1532
1536 virtual void Run() = 0;
1537
1549 virtual uint64_t DoneWait(uint64_t timeoutMilliseconds) = 0;
1550
1552
1557
1562 virtual void ReloadLines(int32_t start = 0, int32_t end = -1) = 0;
1563
1566 virtual int32_t LineCountGet() = 0;
1567
1572 virtual const char* const ProgramGet() = 0;
1573
1581 virtual int32_t SyntaxErrorLineNumberGet() = 0;
1582
1590 virtual const char* const LineTextGet(uint32_t lineNumber) = 0;
1591
1598 virtual double FeedRateGet() = 0;
1599
1605 virtual double AccelerationRateGet() = 0;
1606
1611 virtual double DurationGet() = 0;
1612
1624 virtual void Cancel() = 0;
1625
1631 virtual RapidVector<RobotPosition> PlannedPositionsGet(uint64_t startFrame, uint64_t frameCount) = 0;
1632
1641 virtual void UnitsSet(LinearUnits units) = 0;
1642
1650 virtual LinearUnits UnitsGet() = 0;
1651
1658 virtual void WorkOffsetConfigure(GCodeWorkOffset workOffset, Vector3d offsetValues) = 0;
1659
1665 virtual void ActiveWorkOffsetSelect(GCodeWorkOffset workOffset) = 0;
1666
1673
1680
1682 virtual bool IsRunning() = 0;
1683
1686 virtual int32_t ExecutingLineNumberGet() = 0;
1687
1691 virtual void FreeAxisLetterSet(const char gcodeLetter, const int32_t freeAxisIndex) = 0;
1692
1694 virtual void CallbackRegister(Cartesian::GcodeCallback* callback) = 0;
1695
1697 };
1698
1700
1701} // Cartesian namespace
1702} // RapidCode namespace
1703} // RSI namespace
1704
1705#endif // defined(HAS_CARTESIAN_ROBOT)
1706#endif // _CARTESIANROBOT_H
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 GcodeLoad() 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 RobotPosition & ActiveWorkOffsetValuesGet()=0
Gets the actual values of the currently applied offset.
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...
void FreeAxisLetterSet(const char gcodeLetter, const int32_t freeAxisIndex)=0
Map a letter in a Gcode file to a free axis. It will be used to specify the free axis' motion.
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. Or use the exception thrown by Load or LoadF...
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.
LinearUnits UnitsGet()=0
Get the currently active unit as set by G20/G21.
void AccelerationRateSet(double programmingUnitsPerMinuteSquared)=0
REQUIRED before Load() or LoadFile(). Sets the target acceleration for the machine (units/minute^2)....
double AccelerationRateGet()=0
Gets the target acceleration for the machine (GcodeUnitsGet()/minute^2). Rotational only moves are in...
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). Rotational only moves are in (deg...
void LoadFile(const char *const file)=0
Load a G-code program from a file.
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
REQUIRED before Load() or LoadFile() if your g-code does not have 'F' in its contents....
void Load(const char *const text)=0
Load a G-code program from a string.
void Run()=0
Run the loaded G-Code file (or string). The behavior is non-blocking. Use DoneWait() to block.
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(Storage *storage)
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.
bool EqualsOrientation(const Pose &rightHandSide, double tolerance) const
Approximate equality check. Checks whether all components are within the tolerance of each other....
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. Assumes RPY in Radians. To use a different unit, use Quaternion::Quaternion(const ...
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.
Quaternion & Set(const Vector3d &vec, RotationalUnits units=RotationalUnits::Radians)
Assigns the quaternion defined by the Euler Angles into 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. Assumes RPY in Radians....
bool operator==(const Quaternion &rightHandSide) const
Exact equality check. See equals for approximately equal to.
Vector3d ToEuler(RotationalUnits units=RotationalUnits::Radians) const
Gets the Euler Angle representation of this quaternion.
double Magnitude() const
Gets the magnitude of this. sqrt(SumSquares())
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.
bool EqualsOrientation(const Quaternion &rightHandSide, const double tolerance) const
Equality check within tolerance. For orientations q and -q are considered equal.
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 & 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(const Vector3d &rpy, RotationalUnits units=RotationalUnits::Radians)
Euler Constructor (Alternate)
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.
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.
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.
const double ScaleFactorBetweenUnitsGet(RotationalUnits from, RotationalUnits to)=0
Gets scaling for scale factor needed to convert from -> to units by multiplying
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.
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.
double PathVelocityGet()=0
Gets the target velocity for the machine (UserUnits/second).
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).
void SampleCounterWait(uint64_t sampleCount, uint64_t timeoutMilliseconds)=0
Waits for the sample counter of the Robot's main execution thread to incremented by the specified amo...
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.
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...
RobotPosition ActualPositionGet(LinearUnits units=LinearUnits::None)=0
Get the current actual position of the robot from the trajectory executor in the specified units....
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...
void PathPlaneSet(Plane plane)=0
Sets the plane for the purposes of ambiguous cases (arcs >= 180deg). Last set plane or XY plane is de...
Pose ActualPoseGet(LinearUnits units=LinearUnits::None)=0
Get the current actual pose of the robot from the trajectory executor in the specified units....
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...
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.
const RobotPosition & OriginTransformGet()=0
Offset for the origin location.
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....
const RobotPosition & EndEffectorTransformGet()=0
End of Robot to TCP.
void PathArc(const Pose &target, double radius, RotationDirection direction)=0
Appends an arc on to the current on the PathPlaneGet() plane XY by default.
void PathClear()=0
Clears out all loaded lines and arcs from the path. Part of the PathMotion method group.
void PathUnitsSet(LinearUnits units)=0
Defines the units Cartesian Path Motion is in.
Pose CommandPoseGet(LinearUnits units=LinearUnits::None)=0
Get the current commanded pose of the robot from the trajectory executor in the specified units....
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 MotionCounterWait(uint64_t motionCount, uint64_t timeoutMilliseconds)=0
Waits for the counter increment by the specified amount.
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 &center, RotationDirection direction)=0
Appends an arc on to the current path with end pose about a specific center point.
RobotPosition CommandPositionGet(LinearUnits units=LinearUnits::None)=0
Get the current commanded position of the robot from the trajectory executor in the specified units....
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
void PathArc(const RobotPosition &RobotPosition, const Vector3d &center, 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.
uint64_t SampleCounterGet()=0
Gets the current sample counter of the Robot's main execution thread.
void EndEffectorTransformSet(const RobotPosition &transformPosition)=0
Transform that defines the control point relative to the end end of the current kinematic model with ...
void OriginTransformSet(const RobotPosition &transformPosition)=0
Transform that defines the origin of the robot in the world as a RobotPosition.
const KinematicModel & ModelGet()=0
Get the model this robot was created with.
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 ...
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.
Cartesian::RobotPosition Inverse() const
Gets the inverse of the pose and free axes.
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.
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....
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...
Definition rsi.h:794
Represents multiple axes of motion control, allows you to map two or more Axis objects together for e...
Definition rsi.h:10208
The RapidCode base class. All non-error objects are derived from this class.
Definition rsi.h:178
Represents the error details thrown as an exception by all RapidCode classes. This class contains an ...
Definition rsi.h:105
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 Cartesian Robot/G-Code use.
GCodeWorkOffset
Register names for G-Code work offsets.
RotationalUnits
Unit types. For Cartesian Robot/G-Code use.
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.
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.