Skip to content

ECO62-B Series Parameters and D-H Model

Basic Parameters

Parameter NameParameter Value
Basic ParametersDegrees of Freedom6
Joint Brake TypeJoints 1 to 3: Hard Brake
Joints 4 to 6: Soft Brake
Working Radius/mm355
Payload/kg1
Self-weight/kg3.3
Repeatability/mm±0.01
TCP Line Speed/m/s≤1.3
Typical Power/W≤100
Peak Power/W≤200
Base Dimensions/mmφ102
MaterialAluminum Alloy/ABS
Environmental AdaptabilityOperating Temperature/℃0-45
Operating Humidity 25~85% Non-condensing
Motion Angle Range/°J1-178~+178
J2-169~+104
J3-151~+133
J4-172~+172
J5-172~+172
J6-360~+360
Maximum Angular Velocity/°/sJ1180
J2180
J3180
J4150
J5150
J6150

Ontology Parameters

MDH model frame:

MDH parameters of ECO62-B (modified D-H parameters):

Joint No.(i)ai1(mm)αi1(°)di(mm)θi / offseti(°)Remarks
1001360
2-70-900-90
3148000
41360-58.590
5090710
60-9070.70(B) Standard End Effector (03 Joint Version)
joint_id(i)Lxx (kg*mm^2)Lxy (kg*mm^2)Lxz (kg*mm^2)Lyy (kg*mm^2)Lyz (kg*mm^2)Lzz (kg*mm^2)x (mm)y (mm)z (mm)m (kg)Remarks
11341.83707-1141.532184.121543723.08113-0.706463980.45116-36.0000-13.4700-9.08001.19575
21943.5495-1.2359-3235.968215599.5218-0.573114116.9907119.80000-39.60000.8055
3185.576-2.1952-249.12345023.694-0.1965034.433494.40000-2.00000.413
4166.6853-0.523-0.353273.6738-0.808158.8891-0.1000-16.80003.40000.2386
5224.9708-0.662-0.327693.8259-0.5701211.4858-0.100016.8000-4.30000.2633
632.2687-0.0503-0.015531.9264-0.03424.3730-0.1000-14.60000.0667End flange

Description:

  • m is the mass of the link, kg
  • x is the x-coordinate of the center of mass of link, mm
  • y is the y-coordinate of the center of mass of link, mm
  • z is the z-coordinate of the center of mass of link, mm
  • Lxx,Lxy,Lxz,Lyy,Lyz,Lzz is the principal moment of inertia described in the link frame, kg·mm²

Remarks:

  • Source of data: CAD design values.
  • If the inertial parameters in the center of mass frame are required, they can be calculated based on the parallel axis theorem, as stated below.

Assuming there is an output frame {i}, the center of mass frame coinciding with this coordinate system {i} is {c}, and the coordinates of the center of mass in this frame {i} are Pc=[xc,yc,zc]T, then according to the parallel axis theorem:

Ic=Lim(PcTPcI3×3PcPcT)

Where,

Li=[LxxLxyLxzLxyLyyLyzLxzLyzLzz]

Distribution and dimensions of joints

The ECO62 robotic arm has six rotating joints, each representing one degree of freedom. As shown in the figure below, the robot joints include the shoulder (joints 1, 2, and 3), the elbow (joint 4), and the wrists (joints 5 and 6).

alt text

Workspace

The workspace of ECO62 is a sphere with a working radius of 355 mm, excluding the cylindrical space directly above and below the base. When determining the installation position of the robot, due consideration must be given to the cylindrical space directly above and below the robot to avoid moving tools into this cylindrical space as much as possible. Furthermore, in actual applications, the motion ranges of all joints are as follows: Joint 1: ±178°; Joint 2: -169° to +104°; Joint 3: -151° to +133°; Joint 4: ±172°; Joint 5: ±172°; Joint 6: ±360°.

alt text

alt text

Motion singularities

Shoulder singularity

When the intersection point of the axes of joint 5 and joint 6 lies on the plane passing through the axis of joint 1 and parallel to the axis of joint 2, the robotic arm enters a shoulder singularity configuration. Indicated point 1: [-24.6, -13.199, 77.911, -51.913, 1.997, 1.110], as shown in the figure below.

Shoulder singularity

Elbow singularity

When the intersection point of the axes of joint 5 and joint 6 lies on the plane formed by the axes of joint 2 and joint 3, which means q3 = 0, and the point format is [x, x, 0, x, x, x], the robotic arm enters an elbow singularity configuration. Indicated point 1: [30, 30, 0, 30, 30, 30], as shown in the figure below.

Elbow singularity

Wrist singularity

When the axes of joint 4 and joint 6 are parallel, which means q5 = 0, and the point format is [x, x, x, x, 0, x], the robotic arm enters a wrist singularity configuration. Indicated point 1: [-90, -45, 90, 0, 0, 0], as shown in the figure below.

Wrist singularity

Boundary singularity

When the end of the robotic arm reaches the farthest reach, which means q3 = 0 and q5 = 0, and the point format is [x, x, 0, x, 0, x], the robotic arm enters a boundary singularity configuration. Indicated point 1: [0, 40, 0, 0, 0, 0], as shown in the figure below.

Boundary singularity 1

Load curves

The following figure represents the end load curve of the ECO62-B robotic arm. Here, L refers to the radial distance of the end load's center of mass relative to the end flange plane, and Z refers to the normal distance relative to the end flange plane.

ECO65-B