Class RobotParam¶
Defined in File KinematicsApi.h
Class Documentation¶
-
class RobotParam¶
struct to keep parameters for a robot.
Public Functions
-
inline RobotParam()¶
Constructor to initialize an RobotParam object with default parameters.
Public Members
-
TCHAR robotName[constants::KinematicsDefinition::ROBOT_NAME_MAX_LENGTH]¶
Name of the robot.
-
int robotId¶
This ID is used to identify the robot in the kinematics engine. The ID should be unique among all robots in the engine.
-
constants::RobotModel robotType¶
Type of the robot; defined by RobotModel.
-
int numJoints¶
the number of the joints the robot have.
-
coordinate::CartesianPose baseJointCoordinate¶
base joint coordinate of the robot.
Remark
This coordinate represents the position and orientation of the robot’s base joint, which is typically the first joint in the kinematic chain.
-
LinkParam baseLinkParam¶
base link parameters of the robot.
Remark
This parameter defines the characteristics of the base link, such as its name, origin, and inertia.
-
JointParam jointParams[constants::MAX_NUMBER_OF_JOINT]¶
joint parameters of the robot.
Remark
This array holds the parameters for each joint in the robot’s kinematic chain. Each joint parameter includes information such as the joint’s name, type, axis, origin, limits, and velocity/acceleration constraints.
-
LinkParam linkParams[constants::MAX_NUMBER_OF_JOINT]¶
link parameters of the robot.
Remark
This array holds the parameters for each link in the robot’s kinematic chain. Each link parameter includes information such as the link’s name, origin, and inertia.
-
coordinate::CartesianPose flangeJointCoordinate¶
flange joint coordinate of the robot.
Remark
This coordinate represents the position and orientation of the robot’s end effector or flange joint.
-
ToolRange toolRange¶
global tool limit of the robot.
Remark
This range is used to limit the tool’s motion within a defined workspace. It is typically defined by the robot’s mechanical limits and safety requirements.
-
ToolRange toolSingularRange¶
tool limit of the robot that only evaluate in a continuous path motion for avoiding singular points.
Remark
This range is used to avoid singularities during continuous path (CP) motion.
-
coordinate::CartesianPose workCoordinate¶
work coordinate of the robot.
Remark
This coordinate is used to define the robot’s workspace and is typically aligned with the robot’s base or a specific workpiece. The work coordinate is defined by its origin and orientation in Cartesian space.
-
coordinate::CartesianPose toolCoordinate¶
tool coordinate of the robot.
Remark
This coordinate is used to define the position and orientation of the tool attached to the robot’s end effector. The tool coordinate is defined by its origin and orientation in Cartesian space, relative to the robot’s base or work coordinate.
-
inline RobotParam()¶