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
111
113 class RSI_API Vector3d
114 {
115 public:
117 double X;
118
120 double Y;
121
123 double Z;
124
127
129 Vector3d(double x, double y, double z);
130
132 Vector3d(const Vector3d& rightHandSide);
133
135 double Dot(const Vector3d& rightHandSide) const;
136
141 Vector3d Cross(const Vector3d& rightHandSide) const;
142
144 Vector3d& Set(double x, double y, double z);
145
147 Vector3d& Set(const Vector3d& rightHandSide);
148
151 bool Equals(const Vector3d& rightHandSide, const double tolerance) const;
152
154 double SumSquares() const;
155
157 double Length() const;
158
161
164
166 Vector3d& operator=(const Vector3d& rightHandSide);
168 bool operator==(const Vector3d& rightHandSide) const;
170 bool operator!=(const Vector3d& rightHandSide) const;
172 Vector3d operator*(double scalar) const;
174 Vector3d& operator*=(double scalar);
176 Vector3d operator+(const Vector3d& rightHandSide) const;
178 Vector3d& operator+=(const Vector3d& rightHandSide);
180 Vector3d operator-(const Vector3d& rightHandSide) const;
184 Vector3d& operator-=(const Vector3d& rightHandSide);
186 Vector3d operator/(double scalar) const;
188 Vector3d& operator/=(double scalar);
191 };
192
194 class RSI_API Quaternion
195 {
196 public:
199
201 double W;
202
205
211 Quaternion(double w, double x, double y, double z);
212
215 Quaternion(const Quaternion& otherQuaternion);
216
220 Quaternion(double w, const Vector3d& v);
221
226 Quaternion(double x, double y, double z);
227
231 Quaternion(const Vector3d& rpy, RotationalUnits units = RotationalUnits::Radians);
232
236 bool operator==(const Quaternion& rightHandSide) const;
237
241 bool operator!=(const Quaternion& rightHandSide) const;
242
246 Quaternion& operator=(const Quaternion& rightHandSide);
247
251 Quaternion operator+(const Quaternion& rightHandSide) const;
252
256 Quaternion& operator+=(const Quaternion& rightHandSide);
257
261 Quaternion operator-(const Quaternion& rightHandSide) const;
262
266 Quaternion& operator-=(const Quaternion& rightHandSide);
267
271 Quaternion operator*(const Quaternion& rightHandSide) const;
272
276 Quaternion operator*(double s) const;
277
282
286 Vector3d operator*(const Vector3d& rightHandSide) const;
287
291
295 double Dot(const Quaternion& rightHandSide) const;
296
300 Quaternion& Set(const Quaternion& otherQuaternion);
301
308 Quaternion& Set(double w, double x, double y, double z);
309
314 Quaternion& Set(double w, const Vector3d& vec);
315
323 Quaternion& Set(double x, double y, double z);
324
329 Quaternion& Set(const Vector3d& vec, RotationalUnits units = RotationalUnits::Radians);
330
335 bool Equals(const Quaternion& rightHandSide, const double tolerance) const;
336
341 bool EqualsOrientation(const Quaternion& rightHandSide, const double tolerance) const;
342
346
350
351
354 double SumSquares() const;
355
358 double Magnitude() const;
359
363
367
368
369
374 static Quaternion FromAngleAxis(double angle, const Vector3d& axis);
375
379 void ToAngleAxis(double& outAngle, Vector3d& outAxis) const;
380
384 Vector3d ToEuler(RotationalUnits units = RotationalUnits::Radians) const;
385
392 static Quaternion FromMatrix(const double* const matrix);
393
394
400 void ToMatrix(double* matrix) const;
401 };
402
404 class RSI_API Pose {
405 public:
408
411
414
417 Pose(const Pose& pose);
418
422 Pose(const Vector3d position, const Quaternion& quaternion);
423
426 Pose(const Vector3d& position);
427
432 Pose(double x, double y, double z);
433
436 Pose(const Quaternion& quaternion);
437
442 bool Equals(const Pose& rightHandSide, double tolerance) const;
443
449 bool EqualsOrientation(const Pose& rightHandSide, double tolerance) const;
450
454 Pose Rotate(const Pose& rightHandSide) const;
455
459 Vector3d operator*(const Vector3d& rightHandSide) const;
460
464 Pose operator*(const Pose& rightHandSide) const;
465
468 Pose Inverse() const;
469 };
470
472 class RSI_API RobotPosition
473 {
474 public:
477
480
486 RobotPosition(const Cartesian::Pose& newPose, const size_t numberOfFreeAxes = 0);
488 RobotPosition(const Cartesian::Pose& newPose, const RapidVector<double>& freeAxes);
494 void AxisValueSet(uint32_t index, double value);
496 double AxisValueGet(uint32_t index) const;
499 };
500
502 class RSI_API KinematicModel
503 {
504 public:
505 virtual const char* const NameGet() const = 0;
506 virtual uint32_t AxisCountGet() const = 0;
507
508 virtual LinearUnits UnitsGet() const = 0;
509 virtual RotationalUnits RotationalUnitsGet() const = 0;
510
511 virtual bool IsConfigured() const = 0;
512
513 virtual const char* const* const ExpectedAxisNamesGet() const = 0;
514 virtual uint32_t ExpectedAxisNamesCountGet() const = 0;
515
516 virtual uint32_t FreeAxisCountGet() const = 0;
517
518 // input function
519 // inputPose requires this to be in robot centric coordinates.
520 // remove tool offset and robot base offset
521 virtual bool InverseKinematicsSolve(const Pose& inputPose, void* outputPointerSolutionVector) const = 0;
522
523 virtual bool InverseKinematicsSolve(const RobotPosition& inputPosition, void* vpSols) const = 0;
524
525 // ouput function
526 // inputJointPositions requires this to be in robot centric coordinates.
527 // apply tool offset and robot base offset
528 virtual void ForwardKinematicsSolve(const double* inputJointPositions, Pose& outputPose) const = 0;
529
530 virtual void ForwardKinematicsSolve(const double* inputJointPositions, RobotPosition& outputPosition) const = 0;
531
532 virtual bool IsArticulated() const = 0;
533 };
534
536 struct RSI_API ModelAxisMapping
537 {
538
539 public:
543
545 double Scaling;
546 static constexpr double DefaultScaling = 1.0;
547
549 double Offset;
550 static constexpr double DefaultOffset = 0.0;
551
553 static constexpr int MaxLabelSize = 16;
554 static constexpr int ExpectedLabelBufferSize = MaxLabelSize + 1;
555
559 char ExpectedLabel[ExpectedLabelBufferSize];
560
562 ModelAxisMapping(int jointIndex);
563
565 ModelAxisMapping(int jointIndex, double scaling, double offset, const char* const label);
566
567 // ModelAxisMapping Destructor.
568 virtual ~ModelAxisMapping() = default;
569 };
570
576 {
577 protected:
578 // Stores implementation details for the KinematicModelBuilder. (Pointer to implementation pattern)
579 struct Storage;
580 Storage* storage;
581
584 KinematicModelBuilder(Storage* storage);
585
586 // Protect the copy constructor, for internal use only.
588
589 public:
590 virtual ~KinematicModelBuilder();
591
592 // Delete the copy-assignment constructor.
593 KinematicModelBuilder& operator=(const KinematicModelBuilder&) = delete;
594
595 // Move constructors
597 KinematicModelBuilder& operator=(KinematicModelBuilder&&) noexcept;
598
603 virtual const KinematicModel& ModelBuild() = 0;
604
608 const KinematicModel& ModelGet();
609
612 void UnitsSet(LinearUnits units);
613
616 LinearUnits UnitsGet() const;
617
620 void RotationalUnitsSet(RotationalUnits units);
621
624 RotationalUnits RotationalUnitsGet() const;
625
628 void LabelSet(const char* const label);
629
632 const char* const LabelGet() const;
633
635 void TransformFromKinematicOriginToRobotOriginSet(const Pose& KinematicOriginToRobotOrigin);
636
638 Pose TransformFromKinematicOriginToRobotOriginGet() const;
639
642 void FreeAxisAdd(const ModelAxisMapping& freeAxis);
643 };
644
659 struct RSI_API LinearJointMapping : public ModelAxisMapping
660 {
661 public:
665
666 LinearJointMapping(int jointIndex, CartesianAxis cartesianCoordinate);
667 LinearJointMapping(int jointIndex, CartesianAxis cartesianCoordinate, double scaling, double offset, const char* const label);
668 };
669
673 {
674 // Stores implementation details for the LinearModelBuilder. (Pointer to implementation pattern)
675 struct Storage;
676 Storage* storage;
677
678 public:
679
684 const KinematicModel& ModelBuild() override;
685
687 void JointAdd(const LinearJointMapping& joint);
688
691 LinearModelBuilder(const char* const label);
693
694 // Move constructors
695 LinearModelBuilder(LinearModelBuilder&& other) noexcept;
696 LinearModelBuilder& operator=(LinearModelBuilder&&) noexcept;
697
698 // Disable copy constructors
699 LinearModelBuilder(const LinearModelBuilder&) = delete;
700 LinearModelBuilder& operator=(const LinearModelBuilder&) = delete;
701 };
702
703 // UNSUPPORTED
704 class RSI_API ArticulatedModelBuilder : public KinematicModelBuilder
705 {
706 // Stores implementation details for the ArticulatedModelBuilder. (Pointer to implementation pattern)
707 struct Storage;
708 Storage* storage;
709
710 public:
711 const KinematicModel& ModelBuild() override;
712 ArticulatedModelBuilder();
713 ~ArticulatedModelBuilder();
714 };
715
734 int32_t LineNumber;
735
740 const char* LineText;
741
751 };
752
765 class RSI_API GcodeCallback
766 {
767 public:
780 virtual void Execute(GcodeCallbackData* data) {};
781
782 virtual ~GcodeCallback() = default; // Virtual destructor for C++ base classes
783 };
784
789 class RSI_API Robot : public virtual RapidCodeObject
790 {
791 public:
792
797
811 static Robot* RobotCreate(MotionController* controller, MultiAxis* multiAxis, KinematicModelBuilder* builder, uint32_t motionFrameBufferSize);
812
817 static Robot* RobotCreate(MotionController* controller, MultiAxis* multiAxis, const char* const modelIdentifier);
818
823 static Robot* RobotCreate(MotionController* controller, MultiAxis* multiAxis, const char* const modelIdentifier, uint32_t motionFrameBufferSize);
824
826 static void RobotDelete(MotionController* controller, Robot* robot);
827
829
830
835
837 static constexpr uint64_t TimeoutForever = 0xFFFFFFFFFFFFFFFF;
838
843 static constexpr uint32_t MotionFrameBufferSizeDefault = 256;
844
849 static constexpr uint32_t MotionFrameBufferSizeMinimum = 50;
851
852
857
862 virtual PathState PathStateGet() = 0;
863
868 virtual bool PathStateWait(PathState stateWaitFor, uint64_t timeoutMilliseconds) = 0;
869
874 virtual bool PathStateWaitChange(PathState stateWaitChange, uint64_t timeoutMilliseconds) = 0;
875
876
881 virtual uint64_t MotionCounterGet() = 0;
882
887 virtual void MotionCounterWait(uint64_t motionCount, uint64_t timeoutMilliseconds) = 0;
888
890 virtual uint64_t SampleCounterGet() = 0;
891
896 virtual void SampleCounterWait(uint64_t sampleCount, uint64_t timeoutMilliseconds) = 0;
897
901 virtual bool IsRunning() = 0;
902
906 virtual bool PathIsRunning() = 0;
907
914 virtual bool MotionDoneGet() = 0;
915
922 virtual uint64_t MotionDoneWait() = 0;
923
931 virtual uint64_t MotionDoneWait(uint64_t timeoutMilliseconds) = 0;
932
938 virtual bool HasError() = 0;
939
944 virtual const char* const ErrorMessageGet() = 0;
945
947
948
952
955 virtual void Resume() = 0;
956
959 virtual void Stop() = 0;
960
963 virtual void EStopAbort() = 0;
964
967 virtual void Abort() = 0;
968
972 virtual void AmpEnableSet(bool enable, int32_t ampActiveTimeoutMilliseconds) = 0;
973
980 virtual void EStop() = 0;
981
983 virtual void ClearFaults() = 0;
984
985
986
990
1000 virtual Pose ActualPoseGet(LinearUnits units = LinearUnits::None) = 0;
1001
1011 virtual RobotPosition ActualPositionGet(LinearUnits units = LinearUnits::None) = 0;
1012
1021 virtual Pose CommandPoseGet(LinearUnits units = LinearUnits::None) = 0;
1022
1031 virtual RobotPosition CommandPositionGet(LinearUnits units = LinearUnits::None) = 0;
1032
1038
1044
1050
1056
1062 virtual Pose ForwardKinematics(const RapidVector<double>& joints) = 0;
1063
1070
1074
1076 virtual const KinematicModel& ModelGet() = 0;
1077
1081 virtual void EndEffectorTransformSet(const Pose& transform) = 0;
1082
1084 virtual void EndEffectorTransformSet(const RobotPosition& transformPosition) = 0;
1085
1089 virtual void OriginTransformSet(const Pose& transform) = 0;
1091 virtual void OriginTransformSet(const RobotPosition& transformPosition) = 0;
1092
1096
1099 virtual const RobotPosition& OriginTransformGet() = 0;
1100
1105 virtual const double ScaleFactorBetweenUnitsGet(LinearUnits from, LinearUnits to) = 0;
1106
1112
1116
1125 virtual void MoveAbsolute(const Pose& absolutePose) = 0;
1126
1127
1137 virtual void MoveRelative(const Pose& relativePose) = 0;
1138
1139
1144
1148 virtual void PathClear() = 0;
1149
1155 virtual void PathVelocitySet(double unitsPerSecond) = 0;
1156
1162 virtual double PathVelocityGet() = 0;
1163
1168 virtual void PathAccelerationSet(double unitsPerSecondSquared) = 0;
1169
1173
1175 virtual double PathAccelerationGet() = 0;
1176
1183 virtual void PathProgrammingModeSet(PathMode mode) = 0;
1184
1191
1198 virtual void PathArc(const Pose& target, double radius, RotationDirection direction) = 0;
1199
1206 virtual void PathArc(const RobotPosition& target, double radius, RotationDirection direction) = 0;
1207
1212 virtual void PathArc(const Pose& target, const Vector3d& center, RotationDirection direction) = 0;
1213
1218 virtual void PathArc(const RobotPosition& RobotPosition, const Vector3d& center, RotationDirection direction) = 0;
1219
1220
1221 // @brief Appends a line on the current path
1225 virtual void PathLine(const Pose& target) = 0;
1226
1227 // @brief Appends a line on the current path
1231 virtual void PathLine(const RobotPosition& position) = 0;
1232
1236 virtual void PathPlaneSet(Plane plane) = 0;
1237
1241 virtual Plane PathPlaneGet() = 0;
1242
1248 virtual void PathLinearScalingSet(double scaleFactor) = 0;
1249
1256 virtual double PathLinearScalingGet()const = 0;
1257
1262 virtual void PathUnitsSet(LinearUnits units) = 0;
1263
1267 virtual LinearUnits PathUnitsGet()const = 0;
1268
1272 virtual double PathProcessLoadedMoves() = 0;
1273
1284 virtual RapidVector<RobotPosition> PathPlannedPositionsGet(uint64_t startFrame, uint64_t frameCount) = 0;
1285
1290 virtual double PathDurationGet() = 0;
1291
1297 virtual void Run() = 0;
1298
1315 virtual uint32_t MotionFrameBufferSizeGet()=0;
1316
1318
1321
1322 };
1323
1327 class RSI_API Gcode : public virtual RapidCodeObject
1328 {
1330 public:
1335
1340 virtual void FeedRateSet(double programmingUnitsPerMinute) = 0;
1341
1347 virtual void AccelerationRateSet(double programmingUnitsPerMinuteSquared) = 0;
1348
1356
1360 virtual void Load(const char* const text) = 0;
1361
1365 virtual void LoadFile(const char* const file) = 0;
1366
1374 virtual void Run() = 0;
1375
1387 virtual uint64_t DoneWait(uint64_t timeoutMilliseconds) = 0;
1388
1390
1395
1400 virtual void ReloadLines(int32_t start = 0, int32_t end = -1) = 0;
1401
1404 virtual int32_t LineCountGet() = 0;
1405
1410 virtual const char* const ProgramGet() = 0;
1411
1419 virtual int32_t SyntaxErrorLineNumberGet() = 0;
1420
1428 virtual const char* const LineTextGet(uint32_t lineNumber) = 0;
1429
1436 virtual double FeedRateGet() = 0;
1437
1443 virtual double AccelerationRateGet() = 0;
1444
1449 virtual double DurationGet() = 0;
1450
1462 virtual void Cancel() = 0;
1463
1469 virtual RapidVector<RobotPosition> PlannedPositionsGet(uint64_t startFrame, uint64_t frameCount) = 0;
1470
1479 virtual void UnitsSet(LinearUnits units) = 0;
1480
1488 virtual LinearUnits UnitsGet() = 0;
1489
1496 virtual void WorkOffsetConfigure(GCodeWorkOffset workOffset, Vector3d offsetValues) = 0;
1497
1503 virtual void ActiveWorkOffsetSelect(GCodeWorkOffset workOffset) = 0;
1504
1511
1518
1520 virtual bool IsRunning() = 0;
1521
1524 virtual int32_t ExecutingLineNumberGet() = 0;
1525
1529 virtual void FreeAxisLetterSet(const char gcodeLetter, const int32_t freeAxisIndex) = 0;
1530
1532 virtual void CallbackRegister(Cartesian::GcodeCallback* callback) = 0;
1533
1535 };
1536
1538
1539} // Cartesian namespace
1540} // RapidCode namespace
1541} // RSI namespace
1542
1543#endif // defined(HAS_CARTESIAN_ROBOT)
1544#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...
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.
RSI::RapidCode::Cartesian::Pose Pose
The Robot's Pose.
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:796
Represents multiple axes of motion control, allows you to map two or more Axis objects together for e...
Definition rsi.h:10244
The RapidCode base class. All non-error objects are derived from this class.
Definition rsi.h:180
A wrapper class for the C++ STL vector class that aims to maintain application binary interface....
Definition rsi.h:11822
Represents the error details thrown as an exception by all RapidCode classes. This class contains an ...
Definition rsi.h:107
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.