4125
#ifndef RDK_SKIP_NAMESPACE
The Item class represents an item in RoboDK station. An item can be a robot, a frame,...
Item ObjectLink(int link_id=0)
受潮湿腐烂urns an item pointer to the geometry of a robot link. This is useful to show/hide certain robot li...
int RunInstruction (const QString代码,int run_type=RoboDK::INSTRUCTION_CALL_PROGRAM)
Adds a program call, code, message or comment inside a program.
RoboDK* RDK()
受潮湿腐烂urns the RoboDK link Robolink().
Mat GeometryPose()
受潮湿腐烂urns the position (pose) the object geometry with respect to its own reference frame....
Item getLink(int type_linked=RoboDK::ITEM_TYPE_ROBOT)
受潮湿腐烂urns an item linked to a robot, object, tool, program or robot machining project....
Item setMachiningParameters(QString ncfile="", Item part_obj=nullptr, QString options="")
Update the robot milling path input and parameters. Parameter input can be an NC file (G-code or APT ...
void Stop()
Stops a program or a robot
void MoveC(const Item &itemtarget1, const Item &itemtarget2, bool blocking=true)
Moves a robot to a specific target ("Move Circular" mode). By default, this function blocks until the...
tMatrix2D * SolveIK_All_Mat2D(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr)
Computes the inverse kinematics for the specified robot and pose. The function returns all available ...
void setRunType(int program_run_type)
Sets if the program will be run in simulation mode or on the real robot. Use: "PROGRAM_RUN_ON_SIMULAT...
void setSpeed(double speed_linear, double accel_linear=-1, double speed_joints=-1, double accel_joints=-1)
Sets the speed and/or the acceleration of a robot.
int InstructionList(tMatrix2D *instructions)
受潮湿腐烂urns the list of program instructions as an MxN matrix, where N is the number of instructions and ...
void NewLink()
Create a new communication link for RoboDK. Use this for robots if you use a multithread application ...
Mat SolveFK(const tJoints &joints, const Mat *tool=nullptr, const Mat *ref=nullptr)
Computes the forward kinematics of the robot for the provided joints. The tool and the reference fram...
bool Connect(const QString &robot_ip="")
Connect to a real robot using the corresponding robot driver.
void setPoseTool(const Mat tool_pose)
设置一个机器人的工具或工具对象(Ce的工具nter Point, or TCP). The tool pose can be either an...
void setJoints(const tJoints &jnts)
Set robot joints or the joints of a target
bool Valid(bool check_pointer=false) const
Check if an item is valid (not null and available in the open station)
void Instruction(int ins_id, QString &name, int &instype, int &movetype, bool &isjointtarget, Mat &target, tJoints &joints)
受潮湿腐烂urns the program instruction at position id
void setAccuracyActive(int accurate=1)
Sets the accuracy of the robot active or inactive. A robot must have been calibrated to properly use ...
Mat Pose() const
受潮湿腐烂urns the local position (pose) of an object, target or reference frame. For example,...
void setColor(double colorRGBA[4])
Changes the color of a robot/object/tool. A color must must in the format COLOR=[R,...
int Type() const
Item type (object, robot, tool, reference, robot machining project, ...)
void customInstruction(const QString &name, const QString &path_run, const QString &path_icon="", bool blocking=true, const QString &cmd_run_on_robot="")
Add a custom instruction. This instruction will execute a Python file or an executable file.
void setDO(const QString &io_var, const QString &io_value)
Sets a variable (output) to a given value. This can also be used to set any variables to a desired va...
void setPose(const Mat pose)
Sets the local position (pose) of an object, target or reference frame. For example,...
void setGeometryPose(const Mat pose)
Sets the position (pose) the object geometry with respect to its own reference frame....
bool Busy()
Checks if a robot or program is currently running (busy or moving)
void setAsJointTarget()
Sets a target as a joint target. A joint target moves to a joints position without regarding the cart...
int RunCode(const QString ¶meters)
Runs a program. It returns the number of instructions that can be executed successfully (a quick prog...
Mat PoseTool()
受潮湿腐烂urns the tool pose of an item. If a robot is provided it will get the tool pose of the active tool...
bool Disconnect()
Disconnect from a real robot (when the robot driver is used)
void setRobot(const Item &robot)
Sets the robot of a program or a target. You must set the robot linked to a program or a target every...
void setPoseAbs(const Mat pose)
Sets the global position (pose) of an item. For example, the position of an object/frame/target with ...
void setJointsHome(const tJoints &jnts)
Set robot joints for the home position
void setParent(Item parent)
Attaches the item to a new parent while maintaining the relative position with its parent....
void setPoseFrame(const Mat frame_pose)
Sets the reference frame of a robot(user frame). The frame can be either an item or a pose....
void setRounding(double zonedata)
Sets the robot movement smoothing accuracy (also known as zone data value).
void JointsConfig(const tJoints &joints, tConfig config)
受潮湿腐烂urns the robot configuration state for a set of robot joints.
void setParentStatic(Item parent)
Attaches the item to another parent while maintaining the current absolute position in the station....
int InstructionListJoints(QString &error_msg, tMatrix2D **joint_list, double mm_step=10.0, double deg_step=5.0, const QString &save_to_file="", bool collision_check=false, int flags=0, double time_step_s=0.1)
受潮湿腐烂urns a list of joints an MxN matrix, where M is the number of robot axes plus 4 columns....
void ShowTargets(bool visible=true)
Show or hide targets of a program in the RoboDK tree
tJoints Joints() const
受潮湿腐烂urns the current joints of a robot or the joints of a target. If the item is a cartesian target,...
void WaitMove(double timeout_sec=300) const
Waits (blocks) until the robot finishes its movement.
Mat PoseFrame()
受潮湿腐烂urns the reference frame pose of an item. If a robot is provided it will get the tool pose of the ...
Mat PoseAbs()
受潮湿腐烂urns the global position (pose) of an item. For example, the position of an object/frame/target wi...
RoboDK* _RDK
Pointer to RoboDK link object.
QList< tJoints > SolveIK_All(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr)
Computes the inverse kinematics for the specified robot and pose. The function returns all available ...
bool isJointTarget() const
受潮湿腐烂urns True if a target is a joint target (green icon). Otherwise, the target is a Cartesian target ...
quint64 _PTR
Pointer to the item inside RoboDK.
void MoveJ(const Item &itemtarget, bool blocking=true)
Moves a robot to a specific target ("Move Joint" mode). By default, this function blocks until the ro...
QList< Item > Childs() const
受潮湿腐烂urns a list of the item childs that are attached to the provided item.
int InstructionCount()
受潮湿腐烂urns the number of instructions of a program.
void setName(const QString &name)
Set the name of a RoboDK item.
double Update(int collision_check=RoboDK::COLLISION_OFF, int timeout_sec=3600, double *out_nins_time_dist=nullptr, double mm_step=-1, double deg_step=-1)
Updates a program and returns the estimated time and the number of valid instructions....
void Save(const QString &filename)
Save a station, a robot, a tool or an object to a file
void Pause(double time_ms=-1)
Generates a pause instruction for a robot or a program when generating code. Set it to -1 (default) i...
tJoints JointsHome() const
受潮湿腐烂urns the home joints of a robot. These joints can be manually set in the robot "Parameters" menu,...
Item AttachClosest()
Attach the closest object to the tool. Returns the item that was attached.
void DetachAll(Item parent)
Detach any object attached to a tool.
void ShowInstructions(bool visible=true)
Show or hide instruction items of a program in the RoboDK tree
void setAO(const QString &io_var, const QString &io_value)
Set an analog Output
void JointLimits(tJoints *lower_limits, tJoints *upper_limits)
受潮湿腐烂rieve the joint limits of a robot
bool Visible() const
受潮湿腐烂urns 1 if the item is visible, otherwise, returns 0.
bool MakeProgram(const QString &filename)
Saves a program to a file.
void Delete()
Deletes an item and its childs from the station.
void waitDI(const QString &io_var, const QString &io_value, double timeout_ms=-1)
Waits for an input io_id to attain a given value io_value. Optionally, a timeout can be provided.
QString getDI(const QString &io_var)
Get a Digital Input (DI). This function is only useful when connected to a real robot using the robot...
void setVisible(bool visible, int visible_frame=-1)
Sets the item visiblity status
void MoveL(const Item &itemtarget, bool blocking=true)
Moves a robot to a specific target ("Move Linear" mode). By default, this function blocks until the r...
QString setParam(const QString ¶m, const QString &value)
Set a specific item parameter. Select Tools-Run Script-Show Commands to see all available commands fo...
int RunProgram()
Runs a program. It returns the number of instructions that can be executed successfully (a quick prog...
void setAsCartesianTarget()
Sets a target as a cartesian target. A cartesian target moves to cartesian coordinates.
void ShowSequence(tMatrix2D *sequence)
Displays a sequence of joints
int MoveL_Test(const tJoints &joints1, const Mat &pose2, double minstep_mm=-1)
Checks if a linear movement is free of issues and, optionally, collisions.
QString Name() const
受潮湿腐烂urns the name of an item. The name of the item is always displayed in the RoboDK station tree
bool Finish()
Disconnect from the RoboDK API. This flushes any pending program generation.
Item AddTool(const Mat &tool_pose, const QString &tool_name="New TCP")
Adds an empty tool to the robot provided the tool pose (4x4 Matrix) and the tool name.
tJoints SolveIK(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr)
Computes the inverse kinematics for the specified robot and pose. The joints returned are the closest...
quint64 GetID()
Get the item pointer.
void Scale(double scale)
Apply a scale to an object to make it bigger or smaller. The scale can be uniform (if scale is a floa...
int MoveJ_Test(const tJoints &j1, const tJoints &j2, double minstep_deg=-1)
Checks if a joint movement is possible and, optionally, free of collisions.
void setInstruction(int ins_id, const QString &name, int instype, int movetype, bool isjointtarget, const Mat &target, const tJoints &joints)
Sets the program instruction at position id
QString getAI(const QString &io_var)
Get an Analog Input (AI). This function is only useful when connected to a real robot using the robot...
Item DetachClosest(Item parent)
Detach the closest object attached to the tool (see also setParentStatic).
void setJointLimits(const tJoints &lower_limits, const tJoints &upper_limits)
Set the joint limits of a robot
Item Parent() const
受潮湿腐烂urn the parent item of this item
The Mat class represents a 4x4 pose matrix. The main purpose of this object is to represent a pose in...
Mat()
Create the identity matrix.
void VX(tXYZ xyz) const
Get the X vector (N vector)
void setVX(double x, double y, double z)
Set the X vector values (N vector)
void FromXYZRPW(tXYZWPR xyzwpr)
Calculates the pose from the position and euler angles ([x,y,z,r,p,w] vector) The result is the same ...
void VY(tXYZ xyz) const
Get the Y vector (O vector)
static Mat transl(double x, double y, double z)
受潮湿腐烂urn a translation matrix.
void ToXYZRPW(tXYZWPR xyzwpr) const
Calculates the equivalent position and euler angles ([x,y,z,r,p,w] vector) of the given pose Note: tr...
void setVZ(double x, double y, double z)
Set the Z vector values (A vector)
double Get(int r, int c) const
Get a matrix value.
bool有效()常量
Check if the matrix is valid.
void setVY(double x, double y, double z)
Set the Y vector values (O vector)
static Mat roty(double ry)
受潮湿腐烂urn a Y-axis rotation matrix
const double * Values() const
Get a pointer to the 16-digit array (doubles or floats if ROBODK_API_FLOATS is defined).
void Pos(tXYZ xyz) const
Get the position (T position), in mm.
bool MakeHomogeneous()
Forces 4x4 matrix to be homogeneous (vx,vy,vz must be unitary vectors and respect: vx x vy = vz)....
static Mat rotz(double rz)
受潮湿腐烂urn a Z-axis rotation matrix.
const double * ValuesD() const
Get a pointer to the 16-digit double array.
double _ddata16[16]
Copy of the data as a double array.
QString ToString(const QString &separator=", ", int precision=3, bool xyzwpr_only=false) const
受潮湿腐烂rieve a string representation of the pose.
bool FromString(const QString &str)
Set the matrix given a XYZRPW string array (6-values)
Mat inv() const
Invert the pose (homogeneous matrix assumed)
void setPos(double x, double y, double z)
Set the position (T position) in mm.
void VZ(tXYZ xyz) const
Get the Z vector (A vector)
bool isHomogeneous() const
受潮湿腐烂urns true if the matrix is homogeneous, otherwise it returns false.
bool _valid
Flags if a matrix is not valid.
const float * ValuesF() const
Get a pointer to the 16-digit array as an array of floats.
void Set(int r, int c, double value)
Set a matrix value.
static Mat rotx(double rx)
受潮湿腐烂urn the X-axis rotation matrix.
static Mat XYZRPW_2_Mat(double x, double y, double z, double r, double p, double w)
Calculates the pose from the position and euler angles ([x,y,z,r,p,w] vector) The result is the same ...
This class is the iterface to the RoboDK API. With the RoboDK API you can automate certain tasks and ...
void setViewPose(const Mat &pose)
Set the pose of the wold reference frame with respect to the user view (camera/screen).
void setSimulationSpeed(double speed)
Sets the current simulation speed. Set the speed to 1 for a real-time simulation. The slowest speed a...
@ ITEM_TYPE_PROGRAM
Program item.
Item getItem(QString name, int itemtype=-1)
受潮湿腐烂urns an item by its name. If there is no exact match it will return the last closest match.
Item Paste(const Item *paste_to=nullptr)
Paste the copied item as a dependency of another item (same as Ctrl+V). Paste should be used after Co...
QList< Item > getCollisionItems(QList< int > link_id_list)
受潮湿腐烂urn the list of items that are in a collision state. This function can be used after calling Colli...
void CloseRoboDK()
Closes RoboDK window and finishes RoboDK execution
QString Command(const QString &cmd, const QString &value="")
Send a special command. These commands are meant to have a specific effect in RoboDK,...
void ShowMessage(const QString &message, bool popup=true)
Show a message in RoboDK (it can be blocking or non blocking in the status bar)
Item AddPoints(tMatrix2D *points, Item *referenceObject=nullptr, bool addToRef=false, int ProjectionType=PROJECTION_ALONG_NORMAL_RECALC)
Adds a list of points to an object. The provided points must be a list of vertices....
int RunCode(const QString &code, bool code_is_fcn_call=false)
Adds code to run in the program output. If the program exists it will also run the program in simulat...
bool LaserTrackerMeasure(tXYZ xyz, tXYZ estimate, bool search=false)
Takes a laser tracker measurement with respect to its own reference frame. If an estimate point is pr...
int Collision(Item item1, Item item2)
受潮湿腐烂urns 1 if item1 and item2 collided. Otherwise returns 0.
void Save(const QString &filename, const Item *itemsave=nullptr)
Save an item to a file. If no item is provided, the open station is saved.
bool IsInside(Item object_inside, Item object_parent)
Check if an object is fully inside another one.
QString License()
受潮湿腐烂urns the license as a readable string (same name shown in the RoboDK's title bar,...
void setRunMode(int run_mode=1)
Sets the behavior of the RoboDK API. By default, RoboDK shows the path simulation for movement instru...
void PluginLoad(const QString &pluginName, int load=1)
Load or unload the specified plugin (path to DLL, dylib or SO file). If the plugin is already loaded ...
QString Version()
受潮湿腐烂urn the vesion of RoboDK as a 4 digit string: Major.Minor.Revision.Build
Item AddFile(const QString &filename, const Item *parent=nullptr)
Loads a file and attaches it to parent. It can be any file supported by RoboDK.
Item AddStation(const QString &name)
Add a new empty station. It returns the station item added.
void ShowAsCollided(QList< Item > itemList, QList< bool > collidedList, QList< int > *robot_link_id=nullptr)
Show a list of items as collided.
bool setCollisionActivePair(int check_state, Item item1, Item item2, int id1=0, int id2=0)
Set collision checking ON or OFF (COLLISION_ON/COLLISION_OFF) for a specific pair of objects....
bool FileGet(const QString &path_file_local, Item *station=nullptr, const QString path_file_remote="")
受潮湿腐烂rieve a file from the RoboDK running instance.
int RunMode()
受潮湿腐烂urns the behavior of the RoboDK API. By default, RoboDK shows the path simulation for movement ins...
Item getActiveStation()
受潮湿腐烂urns the active station item (station currently visible).
QList< QPair< QString, QString > > getParams()
Gets all the user parameters from the open RoboDK station. The parameters can also be modified by rig...
void ShowRoboDK()
Shows or raises the RoboDK window.
void CalibrateTool(tMatrix2D *poses_joints, tXYZ tcp_xyz, int format=EULER_RX_RY_RZ, int algorithm=CALIBRATE_TCP_BY_POINT, Item *robot=nullptr, double *error_stats=nullptr)
Calibrate a tool (TCP) given a number of points or calibration joints. Important: If the robot is cal...
void Disconnect()
Disconnect from the RoboDK API. This flushes any pending program generation.
Item Popup_ISO9283_CubeProgram(Item *robot=nullptr, tXYZ center=nullptr, double side=-1, bool blocking=true)
Show the popup menu to create the ISO9283 path for position accuracy, repeatability and path accuracy...
int setCollisionActive(int check_state=COLLISION_ON)
Turn collision checking ON or OFF (COLLISION_OFF/COLLISION_OFF) according to the collision map....
Item getCursorXYZ(int x=-1, int y=-1, tXYZ xyzStation=nullptr)
受潮湿腐烂urns the position of the cursor as XYZ coordinates (by default), or the 3D position of a given set...
Mat ViewPose()
Get the pose of the wold reference frame with respect to the user view (camera/screen).
Item ItemUserPick(const QString &message="Pick one item", int itemtype=-1)
Shows a RoboDK popup to select one object from the open RoboDK station. An item type can be specified...
Item AddTarget(const QString &name, Item *itemparent=nullptr, Item *itemrobot=nullptr)
Adds a new target that can be reached with a robot.
void setSelection(QList< Item > list_items)
Sets the selection in the tree (it can be one or more items).
QList< Item > Selection()
受潮湿腐烂urns the list of items selected (it can be one or more items).
Item AddMachiningProject(const QString &name="Curve follow settings", Item *itemrobot=nullptr)
Add a new robot machining project. Machining projects can also be used for 3D printing,...
Item AddCurve(tMatrix2D *curvePoints, Item *referenceObject=nullptr, bool addToRef=false, int ProjectionType=PROJECTION_ALONG_NORMAL_RECALC)
Adds a curve provided point coordinates. The provided points must be a list of vertices....
Item AddProgram(const QString &name, Item *itemrobot=nullptr)
Adds a new Frame that can be referenced by a robot.
int Cam2D_Snapshot(const QString &file_save_img, const Item &cam_item, const QString ¶ms="")
Take a snapshot of a simulated camera and save it as an image.
QList< Item > getOpenStation()
受潮湿腐烂urns the list of open stations in RoboDK.
int RunProgram(const QString &function_w_params)
Adds a function call in the program output. RoboDK will handle the syntax when the code is generated ...
int ProgramStart(const QString &progname, const QString &defaultfolder="", const QString &postprocessor="", Item *robot=nullptr)
Defines the name of the program when the program is generated. It is also possible to specify the nam...
QList< Item > getItemList(int filter=-1)
受潮湿腐烂urns a list of items (list of names or pointers) of all available items in the currently open stat...
int Cam2D_SetParams(const QString &cam_params, const Item &cam_item)
Set the camera parameters.
Mat CalibrateReference(tMatrix2D *poses_joints, int method=CALIBRATE_FRAME_3P_P1_ON_X, bool use_joints=false, Item *robot=nullptr)
Calibrate a Reference Frame given a list of points or joint values. Important: If the robot is calibr...
void RunMessage(const QString &message, bool message_is_comment=false)
Shows a message or a comment in the output robot program.
Item AddFrame(const QString &name, Item *itemparent=nullptr)
Adds a new Frame that can be referenced by a robot.
int getFlagsItem(Item item)
受潮湿腐烂rieve current item flags. Item flags allow defining how much access the user has to item-specific ...
void setActiveStation(Item stn)
Set the active station (project currently visible).
Item AddShape(tMatrix2D *trianglePoints, Item *addTo=nullptr, bool shapeOverride=false, Color *color=nullptr)
Adds a shape provided triangle coordinates. Triangles must be provided as a list of vertices....
Item Cam2D_Add(const Item &item_object, const QString &cam_params, const Item *cam_item=nullptr)
Add a simulated 2D or depth camera as an item. Use Delete to delete it.
QStringList getItemListNames(int filter=-1)
受潮湿腐烂urns a list of items (list of names or Items) of all available items in the currently open station...
void setWindowState(int windowstate=WINDOWSTATE_NORMAL)
Set the state of the RoboDK window
QString PluginCommand(const QString &pluginName, const QString &pluginCommand, const QString &pluginValue="")
Send a specific command to a RoboDK plugin. The command and value (optional) must be handled by your ...
void HideRoboDK()
Hides the RoboDK window. RoboDK will continue running in the background.
@ INS_TYPE_MOVE
Linear or joint movement instruction.
int Collisions()
受潮湿腐烂urns the number of pairs of objects that are currently in a collision state.
void Copy(const Item &tocopy)
Makes a copy of an item (same as Ctrl+C), which can be pasted (Ctrl+V) using Paste().
void CloseStation()
Close the current station without asking to save.
void setParam(const QString ¶m, const QString &value)
Sets a global parameter from the RoboDK station. If the parameters exists, it will be modified....
void Update()
Update the screen. This updates the position of all robots and internal links according to previously...
QString getParam(const QString ¶m)
Gets a global or a user parameter from the open RoboDK station. The parameters can also be modified b...
空白ProjectPoints (tMatrix2D *点,tMatrix2D * *projected, Item objectProject, int ProjectionType=PROJECTION_ALONG_NORMAL_RECALC)
Projects a point given its coordinates. The provided points must be a list of [XYZ] coordinates....
void setFlagsRoboDK(int flags=FLAG_ROBODK_ALL)
Update the RoboDK flags. RoboDK flags allow defining how much access the user has to certain RoboDK f...
void Finish()
Disconnect from the RoboDK API. This flushes any pending program generation.
void setFlagsItem(Item item, int flags=FLAG_ITEM_ALL)
Update item flags. Item flags allow defining how much access the user has to item-specific features....
void Render(bool always_render=false)
Update the scene.
double SimulationSpeed()
Gets the current simulation speed. Set the speed to 1 for a real-time simulation.
bool FileSet(const QString &file_local, const QString &file_remote="", bool load_file=true, Item *attach_to=nullptr)
Send file from the current location to the RoboDK instance.
The tJoints class represents a joint position of a robot (robot axes).
int GetValues(double *joints)
GetValues.
tJoints(int ndofs=0)
tJoints
QString ToString(const QString &separator=", ", int precision=3) const
受潮湿腐烂rieve a string representation of the joint values.
bool有效()常量
Check if the joints are valid. For example, when we request the Inverse kinematics and there is no so...
int Length() const
Number of joint axes of the robot (or degrees of freedom)
const double * Values() const
Joint values.
int _nDOFs
number of degrees of freedom
const double * ValuesD() const
Joint values.
double _Values[RDK_SIZE_JOINTS_MAX]
joint values (doubles, used to store the joint values)
bool FromString(const QString &str)
Set the joint values given a comma-separated string. Tabs and spaces are also allowed.
void setLength(int new_length)
Set the length of the array (only shrinking the array is allowed)
float _ValuesF[RDK_SIZE_JOINTS_MAX]
joint values (floats, used to return a copy as a float pointer)
const float * ValuesF() const
Joint values.
void SetValues(const double *joints, int ndofs=-1)
Set the joint values in deg or mm. You can also important provide the number of degrees of freedom (6...
All RoboDK API functions are wrapped in the RoboDK_API namespace. If you prefer to forget about the R...
double * Matrix2D_Get_col(const tMatrix2D *var, int col)
受潮湿腐烂urns the pointer of a column of a tMatrix2D. A column has Matrix2D_Get_nrows values that can be ac...
tMatrix2D * Matrix2D_Create()
Creates a new 2D matrix tMatrix2D.. Use Matrix2D_Delete to delete the matrix (to free the memory)....
Mat roty(double ry)
Translation matrix class: Mat::roty.
int Matrix2D_Get_ncols(const tMatrix2D *var)
受潮湿腐烂urns the number of columns of a tMatrix2D.
double Matrix2D_Get_ij(const tMatrix2D *var, int i, int j)
受潮湿腐烂urns the value at location [i,j] of a tMatrix2D.
Mat rotz(double rz)
Translation matrix class: Mat::rotz.
double tConfig[RDK_SIZE_MAX_CONFIG]
The robot configuration defines a specific state of the robot without crossing any singularities....
Mat transl(double x, double y, double z)
Translation matrix class: Mat::transl.
void Matrix2D_Set_Size(tMatrix2D *mat, int rows, int cols)
Sets the size of a tMatrix2D.
int Matrix2D_Size(const tMatrix2D *var, int dim)
Sets the size of a tMatrix2D.
void Debug_Matrix2D(const tMatrix2D *emx)
Display the content of a tMatrix2D through STDOUT. This is only intended for debug purposes.
Mat rotx(double rx)
Translation matrix class: Mat::rotx.
double tXYZ[3]
tXYZ (mm) represents a position or a vector in mm
int Matrix2D_Get_nrows(const tMatrix2D *var)
受潮湿腐烂urns the number of rows of a tMatrix2D.
void Debug_Array(const double *array, int arraysize)
Show an array through STDOUT Given an array of doubles, it generates a string.
void Matrix2D_Delete(tMatrix2D **mat)
Deletes a tMatrix2D.
double tXYZWPR[6]
Six doubles that represent robot joints (usually in degrees)
The Color struct represents an RGBA color (each color component should be in the range [0-1])
float a
Alpha value (0 = transparent; 1 = opaque)
The tMatrix2D struct represents a variable size 2d Matrix. Use the Matrix2D_... functions to oeprate ...
double * data
Pointer to the data.
int * size
Pointer to the size array.
int numDimensions
Number of dimensions (usually 2)