🞴 Engineering Index About Search

Parallel Cable-Driven Robot Kinematics


Parallel cable-driven robots are mechanically fairly simple: a gripper (or some other end effector) is suspended by several cables in a frame, and moves when the cables are pulled or released by motors. There are some relatively well known examples of this, such as SkyCam cameras used for live footage in sports stadiums. It is important to understand the pros and cons of this design. The primary advantages of this design is that the parts in motion can be made extremely light and with low inertia (only cables and the end effector move), and that it is relatively simple to build. On the other hand, the range of motion is limited to a volume enclosed by the frame, and the calculations necessary to achieve a specific desired motion can be complex. In this blog post, I hope to cover some techniques for solving the kinematics of parallel cable robots, and I have a reference implementation of the kinematics in a GitHub repository.

Mechanical Model

The precise configuration of the cables between the frame and end effector relative to each other can greatly affect the range of motion and stability of the robot, especially if there are fewer cables than degrees of freedom or loose cables. Thus, for simplicities sake, this post will be focusing on machines with at least as many cables as degrees of freedom and no loose cables. Note that even with these restrictions, the exact placement of these cables may result in extremely limited or unstable robots. Rotational range of motion can become especially limited.

Another mechanical consideration is the precise mechanics of a single cable. It is fine to assume the cable connects to and swivels around a point on the end effector, since we can fix the end of the cable to a ball joint. However, the same cannot be done on the frame end of the cable, since the cable has to slide at that point. A common solution to this problem is to use a swiveling pulley, which gives us a frictionless wire guide, but it also means that the cable length changes depending on the angle of the cable in addition to the distance to the end (see Fig. 1). Overall, compensating for the swivel pulley mechanism only requires finding an explicit solution to a simple geometry problem, but it is necessary if we want accurate results.

Pulley Swivel Error

Figure 1: The red arc represents the extra cable length due to the cable wrapping around the pulley. Note that the distance from the anchors to the pulley are the same in both cases, but the amount of cable released by the motor differs by the red arcs.

The parameterization of a design will be a list of cables. For each cable, we specify the 3D location of the swiveling pulley , the swivel axis, the pulley radius (all relative to the frame coordinate system), and the 3D location of the cable anchor point (relative to the end effector coordinate system).

Inverse Kinematics

Inverse kinematics refers to the calculations to determine the actuator positions (cable lengths in this case) required to produce a certain desired end effector position. Contrary to most robot configurations, the inverse kinematics are easier to calculate than the forward kinematics. First, the positions of the cable anchor points are transformed from the coordinate space of the end effector to the coordinate space of the frame. This transformation is the "pose" of the end effector and is defined by a translation (the position of the center of the end effector) and a rotation (the orientation around the center of the end effector).

Once the anchor positions are known, we can calculate the length of each wire. If you ignore the pulley term, the length is just the Euclidean distance between the cable source and the anchor. A useful insight is to realize that the pulley and the cable will always be in the same plane, which is fully defined by the swivel axis and the anchor position. Within this plane, we solve for the tangent lines from the cable anchor and the pulley.

Pulley Swivel Error

Figure 2: The tangent point \( P \) can be used to calculate the correct cable length. However, extraneous tangents (dotted lines) must be filtered out.

Once the position of the tangent point of the cable on the pulley is known, the cable length can be calculated as the distance from that point to the cable anchor plus the arc length of the red arc.

Forward Kinematics

The forward kinematics for the parallel cable robot are much less straigtforward. We are interested in finding a pose of the end effector that has the same cable lengths as we measure, which is equivalent to the solution to the equation $$ IK(P) = CL $$ where \( P \) is the pose we are solving for, \( IK \) is the inverse kinematic function described above that calculates the cable lengths of a pose, and \( CL \) is the measured cable lengths.

A general solution is hard to come by since there are discontinuities depending on the configuration of the wires, especially when the swivel pulley model is applied. Thus, gradient descent is used to find a solution. Gradient descent is a technique used to find local minima of functions; in this case, the input to the function would be a guess of the current pose of the end effector, and the output is some function that has a local minimum at true pose of the end effector. The gradient of this function is a value for each of the inputs that points towards lower value of the function. Therefore, by repeatedly shifting our guesses and evaluating the gradient, we can eventually find a guess that is at a local minimum. The function we use is $$ f(P) = ||IK(P) - CL|| $$

When \( IK(P) = CL \) , this function has a value of 0, which increases when the guessed cable lengths are different from the measure ones. Now we just need to find the gradient \( \nabla f \) . An explicit formula for this gradient would be very tedious to write out and hard to validate, so we will use another tool to make this part easier: automatic differentiation. Libraries for various languages exist that will calculate the gradient of a function you have defined. Examples of such packages are ad for Python or the autodiff for Rust, which I used for the reference implementation. The when a function and an input are passed to these libraries, they use the function to calculate its gradient at the input, usually by repeating the calculations with a special value type. The internal workings aside, this means that we can just use the inverse kinematics from the previous section and cable length measurements to define \( f(P) \), and then perform gradient descent to solve the forward kinematics.