The RMP Motion Controller API
CartesianRobotabstract

The CartesianRobot class for Path, G-Code and RapidRobot motion for any actuator. Use MultiAxis::CartesianRobotCreate() to make one. Your kinematic model must be supported by RapidCode. More...

Functions

virtual const char *const KinematicsIdGet ()=0
 The kinematics ID. More...
 
virtual bool GcodeFileLoad (const char *const filePath)=0
 Open a file at the specified file path. Calls GcodeStringLoad() with the contents of the file. More...
 
virtual bool GcodeStringLoad (const char *const text)=0
 Interpret a string as contents of a G-Code file and prepare it for execution. More...
 
virtual const char *const GcodeProgramGet ()=0
 Gets the raw file contents of the last loaded program. More...
 
virtual void GcodeFeedRateSet (double feedRate)=0
 Sets the target feed rate for the machine (units/minute). Same as the "F" Command in a G-Code file. More...
 
virtual double GcodeFeedrateGet ()=0
 Gets the target feed rate for the machine (GcodePathUnitsGet()/minute). More...
 
virtual void GcodeAccelerationSet (double acceleration)=0
 Sets the target acceleration for the machine (units/minute^2). Should be set apprpriately based on your hardware. More...
 
virtual double GcodeAccelerationGet ()=0
 Gets the target acceleration for the machine (GcodePathUnitsGet()/minute^2). More...
 
virtual void GcodeRun (bool blocking)=0
 Run the last loaded item. Optional argument to prevent blocking. Check GcodeIsRunning(); to see if execution is done. More...
 
virtual void GcodeRun ()=0
 Run the last loaded G-Code lines. Default behavior is blocking. This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 
virtual int32_t GcodeExecutingLineNumberGet ()=0
 Returns the line number of the currently executing G-Code line or -1 if there is none. More...
 
virtual void GcodeUnitsSet (RSILinearUnits units)=0
 Set the currently active unit (same as calling G20/G21) More...
 
virtual RSILinearUnits GcodePathUnitsGet ()=0
 Get the currently active unit as set by G20/G21. More...
 
virtual void GcodeProgrammingModeSet (RSIPathMode mode)=0
 Sets the programming mode (Relative/Absolute). More...
 
virtual RSIPathMode GcodeProgrammingModeGet ()=0
 Gets the G-Code programming mode (Relative/Absolute). More...
 
virtual int32_t GcodeErrorLineNumberGet ()=0
 Gets the line number of any errors in the G-Code syntax. More...
 
virtual int32_t GcodeNumberOfLinesGet ()=0
 Returns the total line number count in the last loaded item. More...
 
virtual void GcodeReload ()=0
 Reloads the all lines from the last call to GcodeStringLoad(). Automatically called by GcodeStringLoad(). This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 
virtual void GcodeReload (int32_t startLine, int32_t endLine)=0
 Reloads the lines from the last call to GcodeStringLoad() but only between start and end line numbers. This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 
virtual void GcodeReload (int32_t startLine)=0
 Reloads the lines from the last call to GcodeStringLoad() but only between start line and end of file. This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 
virtual const char *const GcodeLineTextGet (uint32_t lineNumber)=0
 Gives you the text of a specific line from the last loaded program excluding all comments and with only once space between chunks. More...
 
virtual void GcodePlaneSet (RSIPlane plane)=0
 Set the plane for arcs (same as calling G17/G18/G19) More...
 

Run the loaded path lines/arcs. Default behavior is blocking. This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

CartesianPathMotion

See also
PathRun()
Part of the CartesianPathMotion method group. Visit our Topic Page for more information.
virtual void PathRun (bool blocking)=0
 
virtual void PathRun ()=0
 
virtual bool IsRunning ()=0
 Returns whether or not the executor is executing motion. More...
 
virtual void PathClear ()=0
 Clears out all loaded lines and arcs from the path Part of the CartesianPathMotion method group. Visit our Topic Page for more information.
.
 
virtual void PathVelocitySet (double velocity)=0
 Sets the target linear cartesian velocity for each move (UserUnits/second). More...
 
virtual double PathVelocityGet ()=0
 Gets the target velocity for the machine (UserUnits/second). More...
 
virtual void PathAccelerationSet (double acceleration)=0
 Sets the target acceleration for the machine (UserUnits/second^2). Should be set apprpriately based on your hardware. More...
 
virtual double PathAccelerationGet ()=0
 Gets the target acceleration for the machine (UserUnits/second^2). More...
 
virtual void PathProgrammingModeSet (RSIPathMode mode)=0
 Sets the programming mode (Relative/Absolute). More...
 
virtual RSIPathMode PathProgrammingModeGet ()=0
 Gets the programming mode (Relative/Absolute). More...
 
virtual void PathLine (const Pose &pose)=0
 Appends a line on to the current path with end pose. More...
 
virtual void PathLine (const Pose &pose, bool stopAfter, bool online)=0
 Appends a line on to the current path with end pose. More...
 
virtual void PathLine (double x, double y, double z)=0
 Appends a line on to the current path with end x,y,z location. More...
 
virtual void PathLineX (double x)=0
 Appends a line on to the current path along x axis. More...
 
virtual void PathLineY (double y)=0
 Appends a line on to the current path along y axis. More...
 
virtual void PathLineZ (double z)=0
 Appends a line on to the current path along z axis. More...
 
virtual void PathLineXY (double x, double y)=0
 Appends a line on to the current path on xy plane. More...
 
virtual void PathLineXZ (double x, double z)=0
 Appends a line on to the current path on xz plane. More...
 
virtual void PathLineYZ (double y, double z)=0
 Appends a line on to the current path on yz plane. More...
 
virtual void PathArc (RSIRotationDirection direction, const Pose &endPose, const Target &center)=0
 Appends an arc on to the current path with end pose about a specific center. More...
 
virtual void PathArc (RSIRotationDirection direction, double x, double y, double z, double i, double j, double k)=0
 Appends an arc on to the current path with end pose about a specific center. More...
 
virtual void PathArcXY (RSIRotationDirection direction, double x, double y, double i, double j)=0
 Appends an arc on to the current on the XY plane. More...
 
virtual void PathArcXY (RSIRotationDirection direction, double x, double y, double radius)=0
 Appends an arc on to the current on the XY plane. More...
 
virtual void PathArcXZ (RSIRotationDirection direction, double x, double z, double i, double k)=0
 Appends an arc on to the current on the XZ plane. More...
 
virtual void PathArcXZ (RSIRotationDirection direction, double x, double z, double radius)=0
 Appends an arc on to the current on the XZ plane. More...
 
virtual void PathArcYZ (RSIRotationDirection direction, double y, double z, double j, double k)=0
 Appends an arc on to the current on the YZ plane. More...
 
virtual void PathArcYZ (RSIRotationDirection direction, double y, double z, double radius)=0
 Appends an arc on to the current on the YZ plane. More...
 
virtual void PathPlaneSet (RSIPlane plane)=0
 Sets the plane for the purposes of ambigous cases (arcs >= 180deg). Last set plane or XY plane is default. More...
 
virtual RSIPlane PathPlaneGet ()=0
 Gets the plane some arcs will be forced to be on. More...
 
virtual Pose ActualPoseGet ()=0
 Get the actual pose of the robot from the trajectory exectutor. More...
 
virtual Pose CommandPoseGet ()=0
 Get the commanded pose of the robot from the trajectory exectutor. More...
 
virtual void JointsActualPositionsGet (double *positions, uint16_t sz)=0
 Get the actual position of the axes in the underlying MultiAxis. More...
 
virtual void JointsCommandPositionsGet (double *positions, uint16_t sz)=0
 Get the commanded position of the axes in the underlying MultiAxis. More...
 
virtual void InverseKinematics (Pose pose, double *outJoints, uint16_t outJointsSize)=0
 Run the given pose through the current inverse kinematic model to see the joint positions the robot would chooses. More...
 
virtual void SetEndEffectorLength (double length)=0
 Set the extra translation in the Z direction for the initial position of the end effector of the robot. More...
 
virtual void PathUnitsRotationalScalingSet (double scaleFactor)=0
 Sets scaling for ROTATIONAL UNITS between the user units on the machine and units in path motion. More...
 
virtual double PathUnitsRotationalScalingGet ()=0
 Gets scaling for ROTATIONAL UNITS between the user units on the machine and units in path motion. More...
 
virtual void PathUnitsLinearScalingSet (double scaleFactor)=0
 Sets scaling for LINEAR UNITS between the user units on the machine and units in path motion. More...
 
virtual double PathUnitsLinearScalingGet ()=0
 Gets scaling for LINEAR UNITS between the user units on the machine and units in path motion. More...
 
virtual void PathReset ()=0
 Stops the motion and clears our planned moves Visit our Topic Page for more information.
.
 
virtual void PathProcessLoadedMoves ()=0
 
virtual uint64_t PathPlannedPointsGet (double *points, double *times, uint64_t startFrame, uint64_t frameCount)=0
 Get points representing the planned motion in cartesian space that will happen when run is called. More...
 
virtual double PathLoadedMovesExecutionTimeGet ()=0
 Get total (seconds) duration of the planned motion that will happen when run is called. More...
 
virtual Pose PoseFromJoints ()=0
 Get the Actual pose of the robot from the the joint MultiAxis positions. More...
 
virtual bool MotionDoneGet ()=0
 Check to see if motion is done and settled. More...
 
virtual int32_t MotionDoneWait ()=0
 Waits for a move to complete. More...
 
virtual int32_t MotionDoneWait (int32_t timeout_ms)=0
 Waits for a move to complete. More...
 
virtual bool HasError ()=0
 Get the error state of the underlying Trajectory Executor. More...
 
virtual const char *const RetrieveError ()=0
 Get the text of any error in the Trajectory Executor. More...
 
virtual const char *const VersionGet ()=0
 Get the RSI RapidCode version. More...
 
virtual int32_t MpiVersionMajor ()=0
 Get the major MPI version.
 
virtual int32_t MpiVersionMinor ()=0
 Get the minor MPI version.
 
virtual int32_t MpiVersionRelease ()=0
 Get the release MPI version.
 
virtual int32_t RSIVersionMajor ()=0
 Get the major RSI version.
 
virtual int32_t RSIVersionMinor ()=0
 Get the minor RSI version.
 
virtual int32_t RSIVersionMicro ()=0
 Get the micro RSI version.
 
virtual int32_t RSIVersionPatch ()=0
 Get the patch RSI version.
 
virtual int32_t NumberGet ()=0
 Get the zero-based index of this object. ℹ This function is avaliable in RapidCode and RapidSequencer More...
 
virtual int32_t ErrorLogCountGet ()=0
 Get the number of software errors in the error log. More...
 
virtual const RsiError *const ErrorLogGet ()=0
 Get the next RsiError in the log. More...
 
virtual void ErrorLogClear ()=0
 Clear the error log. More...
 
virtual void ThrowExceptions (bool state)=0
 Configure a class to throw exceptions. More...
 
virtual const char *const RsiErrorMessageGet (RSIErrorMessage msg)=0
 Get the RSI-specific error message text for a specific RSIErrorMessage.
 
virtual const char *const ErrorMessageGet (RSIErrorMessage msg)=0
 Get the detailed text message for an RSIErrorMessage.
 
virtual bool WarningMsgCheck (RSIErrorMessage msg)=0
 Check to see if an RSIErrorMessage is a warning (true) or not (false).
 
virtual void Trace (bool state)=0
 Enables/Disables trace output. More...
 
virtual void TraceMaskOnSet (RSITrace maskOn)=0
 Turn on a particular trace output mask. More...
 
virtual bool TraceMaskOnGet (RSITrace maskOn)=0
 Check to see if a particular trace output mask is turned on. More...
 
virtual void TraceMaskOffSet (RSITrace maskOff)=0
 Turn off a particular trace output mask. More...
 
virtual void TraceMaskClear ()=0
 Clear the trace output mask. More...
 
virtual void TraceFileSet (const char *const fileName)=0
 Channels Tracing messages to specified file. More...
 
virtual void TraceFileClose ()=0
 Stops Logging to the file. More...
 
virtual void TraceInjectMessage (RSITrace traceLevel, const char *const message)=0
 Add a message to the Trace Log. More...
 

Description

The CartesianRobot class for Path, G-Code and RapidRobot motion for any actuator. Use MultiAxis::CartesianRobotCreate() to make one. Your kinematic model must be supported by RapidCode.