The RMP Motion Controller APIs
Robotabstract

Represents a collection of joints in Cartesian space with forward and inverse kinematics. This class provides an interface for 3D Path motion for any actuator, whether it be an articulated arm, a linear gantry, or a custom robot. Use Robot Creation Methods to make one using a MotionController, MultiAxis and a kinematic model. More...

Static Functions

static RobotRobotCreate (MotionController *controller, MultiAxis *multiAxis, KinematicModelBuilder *builder, uint32_t motionFrameBufferSize)
 Create a Robot object to use G-Code, path motion, etc.
 
static RobotRobotCreate (MotionController *controller, MultiAxis *multiAxis, const char *const modelIdentifier)
 
static RobotRobotCreate (MotionController *controller, MultiAxis *multiAxis, const char *const modelIdentifier, uint32_t motionFrameBufferSize)
 
static void RobotDelete (MotionController *controller, Robot *robot)
 Delete a Robot.
 

Functions

PathState PathStateGet ()=0
 Gets the path state of the Robot.
 
bool PathStateWait (PathState stateWaitFor, uint64_t timeoutMilliseconds)=0
 Waits for a specific path state.
 
bool PathStateWaitChange (PathState stateWaitChange, uint64_t timeoutMilliseconds)=0
 Waits for the path state to not be the specified state.
 
uint64_t MotionCounterGet ()=0
 Gets the current motion counter of the Robot.
 
bool MotionCounterWait (uint64_t motionWaitFor, uint64_t timeoutMilliseconds)=0
 Waits for the counter to be greater than or equal to the specified state.
 
bool MotionCounterWaitChange (uint64_t motionWaitChange, uint64_t timeoutMilliseconds)=0
 Waits for the state to change off the specified counter value.
 
bool IsRunning ()=0
 Returns whether or not the robot is in motion (from executor or other source). Can be used to determine if safe to command a new move.
 
bool PathIsRunning ()=0
 Returns whether or not a planned path is being executed. All G-Code gets converted to path. Joint moves aren't path moves.
 
bool MotionDoneGet ()=0
 Check to see if motion is done and settled.
 
uint64_t MotionDoneWait ()=0
 Waits for a move to complete.
 
uint64_t MotionDoneWait (uint64_t timeoutMilliseconds)=0
 Waits for a move to complete.
 
bool HasError ()=0
 Get the error state of the underlying Trajectory Executor.
 
const char *const ErrorMessageGet ()=0
 Get the text of any error in the Trajectory Executor.
 
void Resume ()=0
 Resume an axis.
 
void Stop ()=0
 Stop an axis.
 
void EStopAbort ()=0
 E-Stop, then abort an axis.
 
void Abort ()=0
 Abort an axis.
 
void AmpEnableSet (bool enable, int32_t ampActiveTimeoutMilliseconds)=0
 Enable all amplifiers.
 
void EStop ()=0
 Commands a joint EStop and clears the loaded moves.
 
void ClearFaults ()=0
 Clears the MultiAxis fault then the Robot's error bit.
 
Pose ActualPoseGet ()=0
 Get the current actual pose of the robot from the trajectory executor, in the Robot model's units.
 
RobotPosition ActualPositionGet ()=0
 Get the current actual position of the robot from the trajectory executor, in the Robot model's units.
 
Pose ActualPoseGet (LinearUnits units)=0
 Get the current actual pose of the robot from the trajectory executor in the specified units.
 
RobotPosition ActualPositionGet (LinearUnits units)=0
 Get the current actual position of the robot from the trajectory executor in the specified units.
 
Pose CommandPoseGet ()=0
 Get the current commanded pose of the robot from the trajectory executor, in the Robot model's units.
 
RobotPosition CommandPositionGet ()=0
 Get the current commanded position of the robot from the trajectory executor, in the Robot model's units.
 
Pose CommandPoseGet (LinearUnits units)=0
 Get the current commanded pose of the robot from the trajectory executor in the specified units.
 
RobotPosition CommandPositionGet (LinearUnits units)=0
 Get the current commanded position of the robot from the trajectory executor in the specified units.
 
RapidVector< double > JointsActualPositionsGet ()=0
 Get the actual positions of the axes in the underlying MultiAxis.
 
RapidVector< double > JointsCommandPositionsGet ()=0
 Get the commanded positions of the axes in the underlying MultiAxis.
 
RapidVector< double > InverseKinematics (Pose pose)=0
 Run the given pose through the current inverse kinematic model to see the joint positions the robot would choose.
 
RapidVector< double > InverseKinematics (RobotPosition pose)=0
 Run the given pose through the current inverse kinematic model to see the joint positions the robot would choose.
 
Pose ForwardKinematics (const RapidVector< double > &joints)=0
 Get the Actual pose of the robot from the the joint MultiAxis positions.
 
RobotPosition ForwardKinematicsPosition (const RapidVector< double > &joints)=0
 Get the Actual position of the robot from the the joint MultiAxis positions.
 
const KinematicModelModelGet ()=0
 Get the model this robot was created with Visit our Topic Page for more information.


 
void EndEffectorTransformSet (const Pose &transform)=0
 Transform that defines the control point relative to the end end of the current kinematic model For example if you have a suction cup EoAT that is 0.15 meters from the mounting point of your robotic arm you could call this method with Pose(0,0,.15) to define the tool z offset.
 
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 homed but what the command MoveAbsolute(0,0,0) to put you at 4 in the x axis, you could call this method with Pose(4,0,0)
 
const PoseEndEffectorTransformGet ()=0
 End of Robot to TCP.
 
const PoseOriginTransformGet ()=0
 Offset for the origin location.
 
const double ScaleFactorBetweenUnitsGet (LinearUnits from, LinearUnits to)=0
 Gets scaling for scale factor needed to convert from -> to units by multiplying

 
void MoveAbsolute (const Pose &absolutePose)=0
 Executes a point-to-point absolute motion in cartesian space.
 
void MoveRelative (const Pose &relativePose)=0
 Executes a point-to-point motion relative to the current end effector Pose.
 
void PathClear ()=0
 Clears out all loaded lines and arcs from the path. Part of the PathMotion method group. Visit our Topic Page for more information.
.
 
void PathVelocitySet (double unitsPerSecond)=0
 Sets the target linear cartesian velocity for each move (UserUnits/second).
 
double PathVelocityGet ()=0
 Gets the target velocity for the machine (UserUnits/second).
 
void PathAccelerationSet (double unitsPerSecondSquared)=0
 Sets the target acceleration for the machine (UserUnits/second^2). Should be set appropriately based on your hardware.
 
double PathAccelerationGet ()=0
 Gets the target acceleration for the machine (UserUnits/second^2).
 
void PathProgrammingModeSet (PathMode mode)=0
 Sets the programming mode (Relative/Absolute).
 
PathMode PathProgrammingModeGet ()=0
 Gets the programming mode (Relative/Absolute).
 
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 PathArc (const RobotPosition &target, double radius, RotationDirection direction)=0
 Appends an arc on to the current on the PathPlaneGet() plane XY by default.
 
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.
 
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.
 
void PathLine (const Pose &target)=0
 
void PathLine (const RobotPosition &position)=0
 
void PathPlaneSet (Plane plane)=0
 Sets the plane for the purposes of ambiguous cases (arcs >= 180deg). Last set plane or XY plane is default.
 
Plane PathPlaneGet ()=0
 Gets the plane some arcs will be forced to be on.
 
void PathLinearScalingSet (double scaleFactor)=0
 Sets scaling between the input to path motion and output of path motion to the kinematic model.
 
double PathLinearScalingGet () const =0
 Gets scaling between input to path motion and output of path motion to the kinematic model.
 
void PathUnitsSet (LinearUnits units)=0
 Defines the units Cartesian Path Motion is in.

 
LinearUnits PathUnitsGet () const =0
 Gets the units of path motion.
 
double PathProcessLoadedMoves ()=0
 Processes our loaded moves. Used internally and to check whether loaded moves are valid, and must be called before both PathPlannedPositionsGet and PathDurationGet.
 
RapidVector< RobotPositionPathPlannedPositionsGet (uint64_t startFrame, uint64_t frameCount)=0
 Get Positions (see RobotPosition) representing the planned motion in cartesian space that will happen when run is called.
 
double PathDurationGet ()=0
 Get total (seconds) duration of the planned motion that will happen when run is called.
 
void Run ()=0
 Run the loaded path lines/arcs. The behavior is non-blocking. Use Robot.MotionDoneWait() to block.
 
uint32_t MotionFrameBufferSizeGet ()=0
 Gets the TrajectoryExecutor's buffer size in frames, one frame is used per RMP sample period.
 
const char *const VersionGet ()
 Get the RSI RapidCode version.
 
int32_t MpiVersionMajor ()
 Get the major MPI version.
 
int32_t MpiVersionMinor ()
 Get the minor MPI version.
 
int32_t MpiVersionRelease ()
 Get the release MPI version.
 
int32_t RSIVersionMajor ()
 Get the major RSI version.
 
int32_t RSIVersionMinor ()
 Get the minor RSI version.
 
int32_t RSIVersionMicro ()
 Get the micro RSI version.
 
int32_t RSIVersionPatch ()
 Get the patch RSI version.
 
int32_t NumberGet ()
 Get the zero-based index of this object.
 
int32_t ErrorLogCountGet ()
 Get the number of software errors in the error log.
 
const RsiError *const ErrorLogGet ()
 Get the next RsiError in the log.
 
void ErrorLogClear ()
 Clear the error log.
 
void ThrowExceptions (bool state)
 Configure a class to throw exceptions.
 
const char *const RsiErrorMessageGet (RSIErrorMessage msg)
 Get the RSI-specific error message text for a specific RSIErrorMessage.
 
const char *const ErrorMessageGet (RSIErrorMessage msg)
 Get the detailed text message for an RSIErrorMessage.
 
bool WarningMsgCheck (RSIErrorMessage msg)
 Check to see if an RSIErrorMessage is a warning (true) or not (false).
 
void Trace (bool state)
 Enables/Disables trace output.
 
void TraceMaskOnSet (RSITrace maskOn)
 Turn on a particular trace output mask.
 
bool TraceMaskOnGet (RSITrace maskOn)
 Check to see if a particular trace output mask is turned on.
 
void TraceMaskOffSet (RSITrace maskOff)
 Turn off a particular trace output mask.
 
void TraceMaskClear ()
 Clear the trace output mask.
 
void TraceFileSet (const char *const fileName)
 Channels Tracing messages to specified file.
 
void TraceFileClose ()
 Stops Logging to the file.
 
void TraceInjectMessage (RSITrace traceLevel, const char *const message)
 Add a message to the Trace Log.
 

Attributes

RSI::RapidCode::Cartesian::GcodeGcode
 An object to load and run Gcode files.
 

Static Attributes

static constexpr uint64_t TimeoutForever = 0xFFFFFFFFFFFFFFFF
 Use this 64-bit value to wait forever in methods which accept a timeoutMilliseconds parameter.
 
static constexpr uint32_t MotionFrameBufferSizeDefault = 256
 The default size the Robot's trajectory executor buffer. There is one frame per RMP sample period.
 
static constexpr uint32_t MotionFrameBufferSizeMinimum = 50
 The minimum size allowable for the Robot's trajectory executor buffer.
 

Description

Examples
GcodeMotion.cs, HelperFunctions.cs, and PathMotion.cs.

Definition at line 922 of file cartesianrobot.h.