UnderAutomation
Une question ?

[email protected]

Contactez-nous
UnderAutomation
⌘Q
Fanuc SDK documentation
System variables
Documentation home

Current position

Read the current robot position in world coordinates or user frame coordinates, for single or multi-group controllers.

  • World current position
  • User frame current position
  • Multi-group controllers
  • API reference

Read the current robot position in world coordinates or in a specific user frame, for any motion group.

Note: The current position is that of the current tool (UTOOL).

World current position

// Read a current world position
Position worldPosition = robot.Snpx.CurrentPosition.ReadWorldPosition();
// Access the Cartesian position
double x = worldPosition.CartesianPosition.X;
// Access the user tool at this cartesian position
short usertTool = worldPosition.UserTool;
// Access the joint positions
double j1 = worldPosition.JointsPosition.J1;
// Read a current world position of group 2
Position worldPositionG2 = robot.Snpx.CurrentPosition.ReadWorldPosition(2);

User frame current position

ReadUserFramePosition returns the position relative to a specific user frame. Use user frame 15 to get the currently selected user frame from the pendant.

// Read user frame 2 position
Position userFrame = robot.Snpx.CurrentPosition.ReadUserFramePosition(1);
// Access the Cartesian position
double x = userFrame.CartesianPosition.X;
// Access the user tool at this cartesian position
short usertTool = userFrame.UserTool;
// Access the user frame id
short usertFrame = userFrame.UserFrame;
// Access the joint positions
double j1 = userFrame.JointsPosition.J1;
// Read a current world position of group 2
Position userFrameG2 = robot.Snpx.CurrentPosition.ReadWorldPosition(2);

Multi-group controllers

For controllers with multiple motion groups (e.g., robot + positioner), specify the group number:

// Read world position of group 2
Position group2Pos = robot.Snpx.CurrentPosition.ReadWorldPosition(2);
// Read user frame position of group 2
Position group2Frame = robot.Snpx.CurrentPosition.ReadUserFramePosition(1, 2);

API reference

Members of Common.Position :
public class Position {
// Default constructor
public Position()
// Constructor with user frame, tool, joints and cartesian position
public Position(short userFrame, short userTool, JointsPosition jointsPosition, ExtendedCartesianPosition cartesianPosition)
// Cartesian position with extended axes
public ExtendedCartesianPosition CartesianPosition { get; set; }
public override bool Equals(object obj)
public override int GetHashCode()
// Joint values in degrees
public JointsPosition JointsPosition { get; set; }
public override string ToString()
// User frame index
public short UserFrame { get; set; }
// User tool index
public short UserTool { get; set; }
}
Members of Common.JointsPosition :
public class JointsPosition {
// Default constructor
public JointsPosition()
// Constructor with 6 joint values in degrees
public JointsPosition(double j1Deg, double j2Deg, double j3Deg, double j4Deg, double j5Deg, double j6Deg)
// Constructor with 9 joint values in degrees
public JointsPosition(double j1Deg, double j2Deg, double j3Deg, double j4Deg, double j5Deg, double j6Deg, double j7Deg, double j8Deg, double j9Deg)
// Constructor from an array of joint values in degrees
public JointsPosition(double[] values)
public override bool Equals(object obj)
public override int GetHashCode()
// Check if joints position is near to expected joints position with a tolerance value
public static bool IsNear(JointsPosition j1, JointsPosition j2, double degreesTolerance)
// Gets or sets the joint value at the specified index
public double this[int i] { get; set; }
// Joint 1 in degrees
public double J1 { get; set; }
// Joint 2 in degrees
public double J2 { get; set; }
// Joint 3 in degrees
public double J3 { get; set; }
// Joint 4 in degrees
public double J4 { get; set; }
// Joint 5 in degrees
public double J5 { get; set; }
// Joint 6 in degrees
public double J6 { get; set; }
// Joint 7 in degrees
public double J7 { get; set; }
// Joint 8 in degrees
public double J8 { get; set; }
// Joint 9 in degrees
public double J9 { get; set; }
public override string ToString()
// Numeric values for each joints
public double[] Values { get; }
}
Members of Common.ExtendedCartesianPosition :
public class ExtendedCartesianPosition : CartesianPosition {
// Default constructor
public ExtendedCartesianPosition()
// Constructor with position, rotations, and extended axes
public ExtendedCartesianPosition(double x, double y, double z, double w, double p, double r, double e1, double e2, double e3)
// Extended axis 1 value
public double E1 { get; set; }
// Extended axis 2 value
public double E2 { get; set; }
// Extended axis 3 value
public double E3 { get; set; }
public override bool Equals(object obj)
public override int GetHashCode()
public override string ToString()
}
Members of Common.CartesianPosition :
public class CartesianPosition : XYZPosition {
// Default constructor
public CartesianPosition()
// Constructor with position and rotations
public CartesianPosition(double x, double y, double z, double w, double p, double r)
// Constructor with position, rotations and configuration
public CartesianPosition(double x, double y, double z, double w, double p, double r, Configuration configuration)
// Copy constructor
public CartesianPosition(CartesianPosition position)
// Constructor from an XYZ position with rotations
public CartesianPosition(XYZPosition position, double w, double p, double r)
// Position configuration
public Configuration Configuration { get; }
public override bool Equals(object obj)
// Create a CartesianPosition with unknow configuration from a homogeneous rotation and translation 4x4 matrix
public static CartesianPosition FromHomogeneousMatrix(double[,] R)
public override int GetHashCode()
// Check if two Cartesian positions are near each other within specified tolerances
public static bool IsNear(CartesianPosition a, CartesianPosition b, double mmTolerance, double degreesTolerance)
// Normalize an angle to the range ]-180, 180]
public static double NormalizeAngle(double angle)
// Normalize the W, P, R angles to the range ]-180, 180]
public static void NormalizeAngles(CartesianPosition pose)
// P rotation in degrees (Ry)
public double P { get; set; }
// R rotation in degrees (Rz)
public double R { get; set; }
// Convert position to a homogeneous rotation and translation 4x4 matrix
public double[,] ToHomogeneousMatrix()
public override string ToString()
// W rotation in degrees (Rx)
public double W { get; set; }
}
Members of Common.XYZPosition :
public class XYZPosition {
// Default constructor
public XYZPosition()
// Constructor with X, Y, Z coordinates in millimeters
public XYZPosition(double x, double y, double z)
public override bool Equals(object obj)
public override int GetHashCode()
public override string ToString()
// X coordinate in millimeters
public double X { get; set; }
// Y coordinate in millimeters
public double Y { get; set; }
// Z coordinate in millimeters
public double Z { get; set; }
}

Intégrez facilement les robots Universal Robots, Fanuc, Yaskawa, ABB ou Staubli dans vos applications .NET, Python, LabVIEW ou Matlab

UnderAutomation
Contactez-nousLegal

© All rights reserved.