Next Article in Journal
Impact of Near-Fault Seismic Inputs on Building Performance: A Case Study Informed by the 2023 Maras Earthquakes
Previous Article in Journal
Diffusion-Q Synergy (DQS): A Generative Approach to Policy Optimization via Denoised Action Spaces
Previous Article in Special Issue
Cable-Driven Exoskeleton for Ankle Rehabilitation in Children with Cerebral Palsy
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Uncalibrated Visual Servoing for Spatial Under-Constrained Cable-Driven Parallel Robots

by
Jarrett-Scott K. Jenny
* and
Matt Marshall
Department of Robotics and Mechatronics Engineering, Kennesaw State University (KSU), Marietta, GA 30060, USA
*
Author to whom correspondence should be addressed.
Appl. Sci. 2025, 15(18), 10144; https://doi.org/10.3390/app151810144
Submission received: 21 August 2025 / Revised: 11 September 2025 / Accepted: 12 September 2025 / Published: 17 September 2025
(This article belongs to the Special Issue Advances in Cable Driven Robotic Systems)

Abstract

Featured Application

This research directly supports autonomous robotic deployments in dynamic outdoor settings, such as precision agriculture, disaster response, or environmental monitoring, where robust and calibration-free control is essential.

Abstract

Cable-driven parallel robots (CDPRs) offer large workspaces with minimal infrastructure, but their control becomes difficult when the platform is under-constrained and sensing is limited. This paper investigates uncalibrated visual servoing (UVS) with a single monocular camera, asking whether simple global static Jacobians (GSJ) can be sufficient and how an adaptive Jacobian estimator behaves. Two platforms are evaluated: a three-cable (3C) platform and a redundant six-cable du-al-plane platform (RC). Motion-capture (MoCap) validation shows that redundancy improves stability and tracking by reducing platform tilt and making image errors correspond more directly to Cartesian motions. Across static and low-speed tracking tasks, GSJ proved reliable, while a baseline recursive least-squares (RLS) estimator without safety triggers was often unstable. These findings suggest that improving mechanical conditioning may be as important as adding algorithmic complexity, and that carefully estimated global models can suffice in practice. Limitations include the use of a single camera, laboratory conditions, and a baseline RLS variant; future work will evaluate event-triggered adaptation and higher-speed trajectories.

1. Introduction

Cable-Driven Parallel Robots (CDPRs) are a multifaceted class of robotic systems, distinguished by their expansive workspaces, high payload-to-weight ratios, and structurally simple designs [1,2]. By replacing traditional rigid-link mechanisms with tensioned cables, CDPRs significantly reduce moving mass, yielding scalable, cost-effective systems [3,4,5]. These characteristics make them especially well-suited for applications requiring large-scale mobility or field deployment, including construction, manufacturing, rehabilitation robotics, and environmental monitoring [6]. Traditionally, the control of CDPRs has relied on precise mechanical and kinematic modeling, assuming that system parameters (such as cable lengths, anchor attachment points, and the geometry of the moving platform) are accurately known and remain constant during operation [7,8]. Within this framework, inverse kinematics can be employed to compute the necessary cable lengths for achieving a desired end-effector position, allowing for precise kinematics-based trajectory control through coordinated actuation of the motors [9].
In certain deployments, particularly in outdoor, mobile, or field-based applications, CDPRs are subjected to a range of environmental and mechanical variabilities [10,11]. Cable stretch, anchor-point drift, backlash in spooling mechanisms, and structural vibrations can all contribute to discrepancies between the assumed model and the actual configuration. These deviations are especially problematic in under-constrained or lower-degree-of-freedom systems, where the platform’s pose is not directly actuated but instead emerges from the balance of tensions across multiple cables [12,13]. As noted by Carricato and Merlet [14], such systems exhibit complex, nonlinear behaviors that are highly sensitive to small perturbations, making accurate modeling and control particularly challenging without near-perfect calibration. Most conventional CDPR control strategies rely on accurate kinematic calibration, assuming fixed anchor-points, known cable lengths, and rigid structural elements [15]. While such assumptions may hold in controlled laboratory settings, they often break down in real-world scenarios.
To mitigate the discrepancies between modeled and real-world CDPR behavior, researchers have developed a range of model-based calibration procedures aimed at improving control accuracy. For example, Tremblay et al. [16] introduced an eye-in-hand, marker-based vision system that estimates cable lengths and anchor-point locations to support offline calibration. Other notable techniques include drift-compensation methods for planar CDPRs [17] and nonlinear optimization approaches tailored to suspended systems [18]. While these strategies have shown effectiveness under static conditions, they remain fundamentally constrained by their reliance on pre-deployment or offline calibration routines [19,20]. In dynamic or unstructured environments (where factors such as wind, terrain instability, or human interaction introduce continuous variability) such calibrated models rapidly become outdated, limiting their practical utility [21].
To overcome calibration demands, uncalibrated visual servoing (UVS) emerged as a more adaptable extension of early servoing methods [22]. UVS eliminates the need for explicit geometric and camera calibration by estimating the mapping between image-space features and actuator commands from data [23]. Unlike conventional visual servoing approaches that depend on detailed knowledge of robot kinematics and a calibrated visual system [1,11,24], UVS learns this mapping offline or online and can, in principle, adapt during operation [25,26,27]. This makes it particularly well-suited for field-deployed or mobile CDPRs, where structural variability, cable behavior, and shifting visual perspectives can render static calibration impractical or quickly obsolete.
At the core of UVS is the image Jacobian, a matrix that relates actuator-space motion to changes in visual features [28]. While traditional methods compute this Jacobian analytically using known system parameters, UVS estimates it empirically (often via regression) by analyzing how observed image-space features respond to controlled motor inputs [29]. Foundational works by Malis et al. [30] and Santamaria-Navarro et al. [25] demonstrated that this data-driven strategy enables UVS to adapt in real time, offering flexibility in the face of mechanical drift, sensor noise, or dynamic environmental conditions [31].
For CDPRs, the adaptability offered by UVS addresses common sources of performance decay. In real-world deployments, these systems are routinely affected by issues such as cable stretch, backlash, tension loss, anchor-point drift, sensor noise, and environmental variability, each of which can degrade the performance of traditional calibration-based control strategies [13]. UVS mitigates these vulnerabilities by linking control directly to observable visual outcomes rather than relying on fixed geometric or kinematic models [25]. In outdoor or field applications (such as disaster response, agricultural robotics, environmental monitoring), anchor points may shift with terrain changes, cables may slack or stretch unpredictably, and visual noise may distort feature tracking [15]. While conventional systems would require frequent recalibration under such conditions, UVS can update its internal mapping by observing how image-space features respond to actuator inputs, enabling low-maintenance operation with minimal setup requirements.
Extending UVS to spatial CDPRs introduces underactuation and single-view observability issues that can render the image Jacobian ill conditioned near common poses [32]. In principle, these challenges motivate online adaptation of the Jacobian, for example, with Recursive Least Squares (RLS) [23]. In this work, we implement RLS as an online Jacobian estimator but deliberately restrict it to a baseline form with constant forgetting and no event gating. Event gating refers to selectively pausing parameter updates when the data are uninformative or unreliable (such as under weak excitation, poor signal-to-noise ratio, or ill-conditioned geometry). By omitting such safeguards here, we sought to evaluate the raw behavior of RLS against a Global Static Jacobian (GSJ) baseline.
We investigate calibration-free control of a spatial CDPR using a single eye-in-hand camera, with an OptiTrack motion-capture (MoCap) system providing ground truth for evaluation only (never in the loop). We evaluate two controllers: a GSJ estimated offline from small excitation motions and image displacements, and an RLS estimator that updates the Jacobian online on two hardware configurations: (i) a 3-cable (3C) single-plane platform with all anchors coplanar at a common elevation, and (ii) a redundant 6-cable (RC) dual-plane platform (see Figure 1). The RC has vertically separated anchor planes and paired cables (two per corner) driven by the same actuator to increase rotational stiffness. We monitor Jacobian conditioning via the minimum singular value σ m i n ( J ) . Both the 3C and RC platform setup used in experimentation can be seen in Figure 2.
Being static by construction, a GSJ cannot, in principle, reflect arbitrarily large configuration changes without re-estimation. Empirically, however, our GSJ remained robust across the tested scenarios within our test envelope, making it a strong baseline for single-camera UVS. RLS achieved comparable accuracy on successful runs but sometimes over-fits to noisy residuals and produced spurious updates. We therefore regard RLS as promising but fragile, and we discuss an event-triggered variant (gates on excitation, residual SNR, conditioning, and dwell) as future work.
A key mechanical enhancement evaluated is a dual-cable redundant layout that damps undesired rotational modes and reduces pose drift (the mean slow change in the platform’s Degrees of Freedom (DoF) pose (particularly roll/pitch) under near-constant commands due to under-constrained nature, static equilibrium, elasticity, friction, and slack events) near workspace edges, improving the conditioning seen by the visual loop. This mechanical element materially improved closed-loop behavior, most notably helping RLS remain stable more often and brought overall performance closer to what a calibrated kinematics-based controller would reach on similar target sets (see Section 3.1 for RMS and settling-time).
Although prior work shows that visual servoing can improve tracking, it remains unclear how far one can go without calibration. This is especially true for spatial CDPRs, where single-view observability and cable slackness can render the image Jacobian ill-conditioned. Our results address this by contrasting GSJ with a baseline RLS variant. To address under-documented aspects of single-camera UVS on spatial CDPRs. We target three gaps and pose corresponding research questions:
  • Under what operating conditions does a carefully estimated GSJ suffice for accurate tracking, and where does RLS provide benefit?
  • How do redundant per-corner cable pairs (6-cable dual-plane) affect conditioning, oscillation, and tracking behavior?
  • What failure modes arise for RLS (updates under low excitation or noisy residuals), and what diagnostic criteria are needed to make adaptation event-triggered and safe?
We answer these questions using MoCap ground truth for evaluation; two controllers (GSJ; RLS); two platforms (3C; RC); tracking multiple fixed targets at four locations and a moving target test, both with five runs attempted per scenario. We operationalize behavior with standard, reproducible metrics: RMS image error, band + dwell settling time for step commands, and a disturbance residual (jitter) defined as RMS of the high-pass (0.4 s moving average (MA)) component of the error; when motor data are available, we use w k = e k e k 1 J k q k before RMS. (see Section 2). We log estimator internals and key loop signals (period, targets, errors) to enable post hoc analysis (metric definitions in Section 2). Our prior GSJ study emphasized strong static accuracy in world space despite under-constrained pose on a 3C platform, whereas the RLS study showed that an online Jacobian can match GSJ only under good initialization and sufficient excitation; otherwise, it over-fits noise and may fail to converge. The present paper extends those results across two platforms (3C; RC), adds MoCap-ground-truthed metrics, and evaluates simple mechanical aid (redundant cable pairs) that materially improve conditioning and closed-loop behavior.
Put simply, the controller uses what the camera sees (pixel coordinates) to steer the robot, without needing a geometric calibration of the whole mechanism. We compare a fixed mapping from pixels to motors (GSJ) against a version that learns and updates this mapping on the fly (RLS). We also test simple mechanical tweaks that reduce camera jitter and improve controllability.
The remainder of this paper is organized as follows. Section 2 details the system architecture, the GSJ and RLS controllers, mechanical enhancements, and the experimental setup (static and dynamic targets). Section 3 reports results and broader implications across platforms and controllers. Section 4 discusses limitations and outlines an event-triggered, stability-aware RLS design and highlighting directions for future research in robust and adaptive control for CDPRs in dynamic, real-world environments. Section 5 concludes the paper by summarizing the key contributions.

2. Materials and Methods

This section details the complete control and estimation pipeline used in our experiments so that a practitioner can reproduce the results on another cable-driven platform with minimal adaptation. We begin by defining the image-space signals, preprocessing, and a least-squares visual-servo control law that operates purely on camera features. We then present two strategies for obtaining the image Jacobian that converts pixel errors to joint commands: a GSJ, estimated once from excitation motions, and an online RLS estimator with constant forgetting. For each approach we spell out the data collection protocol, estimation equations, numerical safeguards, and implementation defaults (rates, filters, limits). Throughout, we emphasize practical choices that influence conditioning and robustness.
We study two cable-driven platforms: (i) a spatial 3C platform and (ii) a RC, see Figure 1 and Figure 2. A downward-facing, eye-in-hand camera is rigidly attached to the platform; drives operate in position mode with encoder feedback. The control loop runs at a nominal period of 40  ms ( 25  Hz).
At each cycle we detect N feature points { ( u i , v i ) } i = 1 N on a fiducial marker (typically N = 3 or N = 4 ); the controlled image feature is the centroid:
u = 1 / N i = 1 N u i , v = 1 / N i = 1 N v i ,
assembled as p = [ u v ] R 2 . We prefer the centroid over selecting 3–4 fixed points because it is robust to transient point loss and yields a stable 2-DoF image feature for both GSJ and RLS. Raw u , v are smoothed with a 5-sample moving average (MA (5)) before differencing or control with a causal, finite-impulse-response (FIR) moving average of length L (we use L = 5 in all runs). MA ( L ) reduces high-frequency pixel noise and desynchronization artifacts relative to the 25 Hz loop, improving conditioning of Jacobian estimation and stability of the TSVD control update. For any scalar sequence x k (e.g., u k or v k ),
x ~ k = 1 L i = 0 L 1 x k i , k L 1 ,
and we initialize the MA by averaging the available prefix (first k + 1 samples) and run 10 control cycles to initialize J ,   P , and filters before logging; for k < L 1 by averaging the available prefix x ~ k = 1 k + 1 i = 0 k x i . Implement Equation (2) via:
s k = s k 1 + x k x k L , x ~ k = s k L ,
with s L 1 = i = 0 L 1 x i and x k L = 0 for k < L . Here s k is the running sum used to implement MA in O ( 1 ) per step. For the centroid p k = [ u k v k ] , apply MA ( L ) elementwise:
p ~ k = M A L ( p ) k = M A L ( u ) k M A L ( v ) k .
All increments in the RLS model use the smoothed signal, Δ p k = p ~ k p ~ k 1 . The image reference p = [ u v ] is either a fixed setpoint (step) or a time-indexed reference; the image error is e = p p (pixels).
Motor positions are q R m (encoder counts), with m = 3 for the setup we used with our platform. We denote increments by Δ q k = q k q k 1 (counts). Unless otherwise stated, p is in pixels, q in counts, and Jacobians map counts to pixels so that Δ q = J ^ + e is dimensionally consistent.

2.1. Visual-Servo Control Law

The controller closes the loop entirely in the image plane. The control loop is summarized in Figure 3, which shows the image error driving the Jacobian-based pseudoinverse update that generates actuator increments. Given the current estimate of the image Jacobian J ^ R 2 × m , we compute a small setpoint increment
Δ q = J ^ + e , J ^ + = V Σ + U ,
where J ^ = U Σ V is the SVD and
Σ i i + = 1 / σ i , σ i > τ , 0 , otherwise , τ = ε m a x { r , m } σ m a x
with r = 2 rows and machine-epsilon heuristic ε . This truncated-SVD (TSVD) pseudoinverse is numerically robust near weak directions without introducing a tunable damping parameter. TSVD is used only in the control pseudoinverse.
We clip per-motor increments to actuator-safe bounds and integrate them into a commanded setpoint:
Δ q c l i p ( Δ q , | Δ q | m a x ) , q k + 1 c m d = q k c m d + Δ q .
Trials automatically stop when | u u | , | v v | ϵ pix (we use ϵ pix [ 20 ,   22 ]  px depending on scenario). Feature-loss events trigger an immediate or ramped stop via the drive API.
Signals and notation:
  • Image features: p = [ u v ] (pixels) each control cycle. We use either the marker centroid or the average of three tracked points; the control law remains 2 -DoF in image space.
  • Reference: p = [ u v ] (pixels): steps or a time-varying path.
  • Error: e = p p (pixels).
  • Actuators: q R m (encoder counts); q ˙ is finite-difference velocity (counts/s).
  • Image Jacobian: J ^ R 2 × m relates joint velocities to feature velocities:
p ˙ J ^ q ˙ .
What the symbols mean in practice:
  • σ m i n ( J ^ ) (conditioning) indicates how much the image actually responds to joint motions; small values warn of poor leverage or impending slackness.
  • The controller is entirely image-space: no world pose, depth, or camera intrinsics are required for the loop to function.
We report σ m i n ( J ^ ) offline to characterize conditioning; it is not used online to retune the controller in these runs. The control loop per cycle is summarized in Algorithm 1.
Algorithm 1 Pseudocode (Per Cycle) for the visual servoing control loop
1:
p   =   lowpass   ( features ( frame ) ) ;   e   =   p _ ref   p
2:
J = current Jacobian estimate
3:
[U,Σ,V] = svd (J)
4:
Σp = diag (1/σ_i if σ_i > τ else 0)
5:
Jplus   =   V   ×   Σ p   × U’
6:
dq   =   clip   ( Jplus   × e, dq_max_per_motor)
7:
qcmd = qcmd + dq
8:
send_to_drives (qcmd)

2.2. Global Static Jacobian (GSJ)

A single, well-estimated J ^ G S J is often sufficient over a wide region of the workspace. It is simple, robust to noise, and avoids the failure modes of online adaptation when excitation or SNR is low. The idea is to learn the local, linear mapping from joint velocity to image velocity by probing the system around a nominal view.
We identify a fixed mapping from motor velocities to per-point pixel velocities and then reduce it to the centroid feature used online. From a brief nudge sequence we compute pixel velocities s ˙ k R 2 N by finite differencing and dividing by the measured period Δ t k , and motor velocities q ˙ k R m from the log. We solve an ordinary least-squares problem with no intercept:
p ˙ k = J p t s q ˙ k + ν k , J ^ p t s = a r g m i n J k p ˙ k J q ˙ k 2 2 ,
yielding J ^ p t s R 2 N × m . ν k is measurement noise and unmodeled image motion (pixels/s).
Because u ˙ c = 1 / N i u ˙ i and v ˙ c = 1 / N i v ˙ i , the centroid Jacobian is the row-wise average of the per-point rows:
J ^ G S J = 1 / N i = 1 N J ^ u i , 1 / N i = 1 N J ^ v i , R 2 × m .
The centroid Jacobian is the row-wise average of per-point rows (10). We hold J ^ G S J fixed during GSJ runs and use its TSVD pseudoinverse in (5) and (6). The detailed estimation procedure is summarized in Algorithm 2.
(i)
Apply MA (5) to u i , v i before differencing;
(ii)
compute Δ t k from timestamps;
(iii)
drop the first sample and any rows that become NaN/Inf after differencing.
Algorithm 2 Estimation of Global Static Jacobian (GSJ) pseudocode
1:
collect per-point (u_i,v_i) and motor velocities
2:
dotp = diff(pixels)/Δt; dotq = diff(encoders)/Δt
3:
stack P = [dotp_k], Q = [dotq_k]
4:
J _ pts   =   P   ×   Q ^ \ top   ×   ( Q   ×   Q ^ \ top ) ^ { 1}% OLS, no intercept
5:
J_GSJ = [mean_rows_u(J_pts); mean_rows_v(J_pts)]% centroid reduction

2.3. RLS Jacobian Adaptation (Constant Forgetting)

As the robot moves, anchor geometry, cable stretch, and viewing perspective drift slowly. Rather than re-identifying offline, RLS updates the Jacobian in flight, fitting the same model as (8) but recursively.
We fit the incremental relation between image-feature changes and motor-count changes:
Δ p k = J k Δ q k + ϵ k , Δ p k p k p k 1 , Δ q k q k q k 1 .
Each cycle we compute Δ q = J ^ + e with the same TSVD rule as in Section 2.1. Let P k be the covariance (confidence) matrix. ϵ k is the pixel-space innovation (modeling error + noise). With forgetting factor λ ( 0 , 1 ] the covariance-form RLS update we implement is:
denom k = λ + Δ q k P k 1 Δ q k ,
Δ F k = Δ p k J k 1 Δ q k ,
J k = J k 1 + Δ F k ( Δ q k P k 1 ) denom k ,
P k = λ 1 P k 1 P k 1 Δ q k Δ q k P k 1 denom k .
We initialize J 0 from a brief local nudge sequence (same feature and filter as above) and set P 0 = α I 3 ( α [ 10 3 , 10 4 ] ). The forgetting factor is fixed at λ = 0.98 . Rows are updated jointly (matrix form above); no event gating is used. Event gating means we temporarily pause the online Jacobian/RLS update during data that would corrupt the estimate (such as at target steps, when commands are too small to provide excitation, when motors saturate, when image SNR is poor, or when the Jacobian is ill-conditioned). Control continues normally; only the parameter update is paused. We did not use gating in this study; we analyze its potential benefits in Section 3.3. In preliminary tests,   λ = 0.96 adapted faster but produced overshoot/oscillation ( 30 35   p x ) , whereas λ = 0.98 yielded smoother trajectories and comparable steady-state error; we therefore use λ = 0.98 in all following experiments. These observations match our prior findings [29]. For clarity, the matrix-form implementation is summarized in Algorithm 3.
Trials stop when | u u | , | v v | 22  px. Feature-loss events trigger a stop as exposed by the drive. Per cycle we log: time; encoder counts q ; raw and filtered u , v (and the four corner points); the target ( u , v ) ; error ( u u , v v ) ; the current J (all entries); λ ; and the measured loop period. These are the exact fields used for our plots and metrics in Section 3.
These safeguards never block updates; they simply keep the numbers well-behaved:
  • Covariance caps: clip eigenvalues of P k to [ P m i n , P m a x ] (example: [ 10 6 , 10 6 ] ) to prevent blow-ups or collapse and, if q k is very small, temporarily set λ   1 for that sample (memory-only).
  • Conditioning (Offline Analysis): the minimum singular value σ m i n ( J ) of the logged Jacobian estimate, summarized per scenario; this quantity is used only for analysis, not in-loop.
  • Update magnitude monitor: track Δ J ^ k F = J ^ k J ^ k 1 F ; a spike indicates low SNR or a transient.
Initialization sequence (what to actually do on the bench):
1.
Warm up filters for 0.5 1  s to stabilize p and p ˙ .
2.
Perform brief micro-nudges on each motor to elicit 10 15  px/s image velocities; collect 0.3 0.5  s of ( p ˙ , q ˙ ) .
3.
Solve a tiny ridge LS for the two rows to set J ^ 0 ; set P 0 = α I with α [ 10 3 , 10 4 ] .
4.
Start control and run (12)–(15) each cycle; assemble J ^ k and use it in (9).
What the parameters mean:
  • λ controls memory: lower λ adapts quickly but can over-fit noisy residuals if excitation is weak.
  • P 0 sets initial confidence: larger α means it will trust data quickly; too small makes the estimate sluggish.
  • Normalizing q k (e.g., rescaling counts/s per motor to unit variance) is optional but can improve conditioning and make λ feel more consistent across axes.
Algorithm 3 Matrix-form RLS pseudocode (Per Cycle)
1:  
# incremental RLS (2 × m J), per cycle
2:  
dq _ meas   =   q [ k ]     q [ k 1]
3:  
df   =   p [ k ]   p [ k   1] # p = [u v]^T after low-pass
4:  
den   =   λ   +   dq _ meas   × P   × dq_meas
5:  
Δ F   =   df     J   × dq_meas
6:  
J   =   J   +   ( Δ F   ×   ( dq _ meas   ×   P))/den
7:  
P   =   ( P     P   ×   dq _ meas   ×   dq _ meas   × P/den)/λ
8:  
# control
9:  
e   =   p _ ref   p
10:
dq   =   clip (   J ^ +   × e)
11:
qcmd += dq
All quantities above are computable from the logs we provide: p ,   p ,   e ,   q ,   J ^ ,   λ , and the loop period. We derive p ˙ , q ˙ by finite-difference, compute σ m i n ( J ^ ) by SVD and analyze Δ J ^ F offline. No commanded inputs or tension sensors are required for the pipeline as described. Smoothing p k with M A ( L = 5 ) reduces white measurement-noise variance by 1 / L but attenuates and delays increments Δ p k p k p k 1 . In (11)–(15), this scales the innovation Δ F k and increases its correlation, which (i) decreases spurious updates in low-SNR regimes, while (ii) modestly slowing adaptation (effective memory increases by roughly the MA group delay). Empirically this helps when excitation is weak; to compensate one can raise λ slightly (such as 0.98 → 0.985) or gate updates on residual SNR/conditioning (Section 4). The practical parameter values used in our experiments are summarized in Table 1. RLS may be combined with safety gates that pause updates when excitation is weak, geometry is ill-conditioned, or residuals are noisy. In this work, we omit such safeguards to evaluate the raw, baseline RLS behavior, providing a calibration-free benchmark consistent with how UVS has been studied in serial robots. The frequent divergence of RLS in our results suggests that event gating or related safeguards may be beneficial; our baseline results establish why such measures are required in CDPRs.

2.4. Experimental Platforms and Instrumentation

We tested on two hardware configurations: (i) a spatial 3C (underactuated pose), and (ii) a RC platform with paired cables per corner to increase rotational stiffness. Anchor pulleys form an equilateral triangle, 2400 mm apart and mounted at 1650 mm elevation. The test area at the triangle centroid measures 1150 mm × 1150 mm and is raised 370 mm above ground. An 8-camera OptiTrack Flex 3 system samples at 100 Hz (±0.20 mm) to log platform, targets, and anchors; MoCap is used only for evaluation.
The camera is eye-in-hand, rigidly attached to the platform, facing downward. We track either a centroid or three points on a fiducial (ArUco) to compute the image features p = [ u | v ] per cycle. We smooth features online with MA (5) (see Section 2.1). We keep the same acquisition and extraction settings as our prior UVS papers.
An OptiTrack system (8 cameras, 100 Hz) records the 3D pose of (a) the platform reference frame, (b) each visual target, and (c) each anchor pulley location. MoCap is never used in the loop only for evaluation and for documenting anchor/target geometry. We export synchronized CSVs with controller logs using a shared wall clock and timestamp alignment (nearest-neighbor sync; ± 10 20 ms typical).
The control node runs on an embedded GPU SBC (same class as prior work), communicating with winch drives over a low-latency link. Drives are position-mode with encoder feedback (counts). Each loop executed at 25 Hz, with average computation times of 40 ms for the GSJ update and 20 ms for the RLS update. In both cases, the limiting factor was image acquisition, not numerical computation, indicating that control law complexity did not constrain throughput in our setup.
For dynamic trials we reuse the prior circular target protocol: a fiducial on a motorized turntable at fixed radius r t , rotating at one revolution every 90 s (angular speed 0.07 rad/s). This yields a low, steady image-velocity challenge while keeping the target fully visible. In this study, target pose and trajectory are also recorded by MoCap (new vs. prior work), so both image-space and world-space tracking errors are available.
We evaluate two calibration-free IBVS controllers:
1.
Global Static Jacobian (GSJ): a single J ^ G S J R 2 × m is identified offline from small excitation motions (nudges) and held fixed during runs; control uses the TSVD pseudoinverse J ^ G S J + as in Section 2.1.
2.
Recursive Least Squares (RLS): the image Jacobian is adapted online via matrix-form RLS with constant forgetting λ (typ. 0.98), initialized from a brief local nudge set; numerical hygiene and conditioning-aware damping follow Section 2.3.
Both controllers use identical feature processing and rate limits. The GSJ/RLS implementations follow the earlier UVS/RLS methodology with our added conditioning monitors; the ungated design choice is deliberate to study raw behavior vs. GSJ.
We consider two scenarios on each platform:
Static targets: four distinct target locations (two near-center and two near-edge positions chosen to stress conditioning), five independent runs per target for each controller.
Moving target: a single circular trajectory as above; five independent runs for each controller. A fiducial follows a repeatable low-speed circular trajectory; for each controller we run five trials consisting of: converge to the target at rest, start the motion, track for one full revolution ( 90  s), stop, and log an additional 3–5 s while static to measure residual bias.
Ideally, the platform remains horizontal so that image-plane error correlates tightly with Cartesian error. In practice, under-constrained pose is the result of its static equilibrium and thus allows small tilts and roll/pitch coupling, partially decoupling image-plane error from Cartesian error; we quantify the impact with MoCap in Section 3.

2.5. GSJ Identification and RLS Initialization

GSJ: With the target centered, we perform symmetric motor nudges ( ± Δ q i ) producing 15 –30 px image shifts; we estimate J ^ G S J in velocity form via ridge LS (small γ ), rejecting samples with q ˙   <   τ q or image spikes at near-zero q ˙ . The resulting J ^ G S J is frozen for all GSJ runs on that platform.
RLS: We warm up filters (0.5–1 s), collect a short micro-nudge set, solve a tiny ridge LS for J ^ 0 , set P 0 = α I ( α [ 10 3 , 10 4 ] ), and update rows with constant- λ RLS each cycle. No event gating is used; we rely on conditioning-aware damping and covariance caps for numerical safety.
Experimental Procedures, Static-target trials (per run): (1) Load controller (GSJ or RLS) and initialize as above; (2) select one of the four target locations; (3) start the loop and step the reference to center the marker; (4) hold for 8–12 s after first settling (or same wall-clock for all runs); (5) return to neutral pose. All signals and MoCap are logged continuously.
Moving-target trials (per run): (1) Converge to the target at rest; (2) start the turntable; (3) track for one full revolution ( 90 s); (4) stop; (5) log another 3–5 s while the target is static to measure residual bias. Image-space errors and MoCap ground truth are recorded throughout.

2.6. Signals Logged and Synchronization

Each cycle we log: time, q (encoder counts), p = [ u | v ] (raw and filtered), p , e , current J ^ (all entries), λ (RLS), control period Δ t , rate-limited Δ q , and basic status flags (feature validity). MoCap logs ( X , Y , Z ) of the platform, each target, and each anchor. Timestamps are synchronized by aligning to the controller wall clock (interpolating MoCap to controller stamps).
We report both image-space and world-space performance:
  • RMS image error (px): R M S ( e ) over the post-transient window.
  • 95% settling time (static steps): first time the normed error stays within 5% of the commanded step amplitude for 1 s.
  • Disturbance residual (px): low-pass RMS of e ~ = e J ^ Δ q f f , where Δ q f f is the finite-difference motor motion; filtered at 2–3 Hz (zero-phase).
  • MoCap position error (mm): Euclidean distance between platform optical-center proxy and target in the world frame (static); radial tracking error vs. MoCap target trajectory (moving).
Per target/scenario/controller we summarize mean ± SD across the five runs; we also report failure counts (target loss, safety abort). Jitter is looked at as well, which for us is the RMS of the high-frequency part of the tracking error after the system has locked/settled. In plain terms, how much the platform wiggles around the nominal track once it is on target (mm in MoCap, px in the image plane). If residual is available, it is the RMS of the high-frequency unmodeled image motion.
Relative to the two prior UVS papers we follow the same hardware class, eye-in-hand vision, feature tracking, and GSJ/RLS estimation approach, but we limit targets to four locations with five runs per scenario, and we now capture MoCap ground truth for the platform, targets, and anchors in every trial. Thus, all figures can be reproduced both in image space and in the world frame without relying on model calibration.

3. Results

3.1. Redundant Cable Analysis, Static Target

The results of the 3C platform and RC platform can be seen in Table 2. For the global servo (GSJ), redundancy reduces post-window image RMS (RMS of Δ U ,   Δ V after the first continuous in-band dwell (or last 1 s if never settled)) from 12.31 px to 8.20 px (33%), with a comparable median settling time median 2.44 s vs. 2.00 s for GSJ; 3.38 s vs. 2.30 s for RLS. t s e t t l e is based on image-plane criteria and may not reflect Cartesian settling under tilt. This explains longer settle times observed for RC in some cases due to stricter image dwell even when MoCap indicates small world-space error. For the RLS controller, redundancy increases settle success (0.33 vs. 0.14) and reduces post-window RMS from 59.17 px to 31.52 px (47%), though the median settling time among settled segments is longer (3.38 s vs. 2.30 s). Overall, GSJ outperforms RLS on both platforms in settle rate and post-window RMS, and redundancy (RC) consistently improves both controllers’ post-entry image accuracy ( ( u u * ) 2 + ( v v * ) 2 over the post window) from GSJ: 12.31 → 8.20 px and RLS: 59.17 → 31.52 px.
Figure 4 shows us the conditioning versus disturbance residual. Each point is one analysis segment. The horizontal axis is the mean smallest singular value of the Jacobian over the segment, a simple conditioning score where larger values mean better actuation authority in all image-plane directions. The vertical axis is the residual RMS image error (px) after subtracting the motion predicted by the commanded joint change, so smaller values mean less unmodeled behavior (disturbances, modeling mismatch, discretization, noise). Marker/color encode controller (GSJ vs. RLS) and cable set (3C vs. RC). Figure 5 shows the distribution of the mean minimum singular value of the image Jacobian, σ m i n   ( J ) , computed per segment. RC tests shift σ m i n   ( J ) upward relative to 3C, indicating better local conditioning. This structural benefit holds for both controllers (GSJ and RLS) and helps explain the improved dwell/settle behavior observed with RC.
Read the plots in Figure 4 as right and down is good. The x-axis reports how well-conditioned the kinematics were during a segment; the mean of the smallest singular value of the Jacobian. When this value is larger, the controller has authority in all directions and is less fragile to noise or modeling errors. The y-axis is the residual RMS image error after removing the portion of the error change that our model predicts from the commanded motion; what’s left reflects unmodeled effects such as cable friction/elasticity, bias in the Jacobian, timing/discretization, and measurement noise. In the full-scale view (a), a handful of large residual spikes appear only when the system is very poorly conditioned, and they occur with RLS; evidence that the adaptive law is sensitive in those regions. The zoomed view (b) shows the bulk of the data: GSJ (both 3C and RC) forms a tight cluster at high conditioning with modest residuals, while RLS sits at lower conditioning with a wider scatter. Adding redundancy (RC) shifts the RLS points toward higher conditioning and lower residuals though not to the same compactness as GSJ. The overall trend across controllers is a gentle downward slope with increasing conditioning, consistent with the intuition that better kinematic conditioning reduces unmodeled error.
Post-window image-error RMS is identified and plotted in Figure 6. Each box summarizes segments for GSJ and RLS under 3C and RC hardware. The metric on the y-axis is the RMS of the image error ( U ,   V ) , MA-filtered component errors (px) used for RMS, over a post window: for settled segments this begins one dwell after the first continuous in-band entry (first time both u u * and v v * fall inside the band ( ± 20 22 px) and stay 1 s); for unsettled segments it is the final 1 s of the segment. Boxes show the median and inter-quartile range; whiskers are 1.5 × IQR; isolated markers are outliers. GSJ exhibits the lowest medians and narrowest spread. RLS with 3C has the largest values and more outliers; adding redundancy (RLS-RC) reduces both the typical RMS and its variability relative to RLS-3C. Treat the vertical axis as how much the error wiggles once it should be quiet. Shorter, lower boxes indicate a steadier hold after entry/settle. Compare left-to-right: GSJ stays low and compact for both 3C and RC; RLS sits higher and is more scattered on 3C, with a clear improvement when moving to RC (box shifts downward and tightens). Outlier points flag occasional bursts of unmodeled behavior; these are concentrated with RLS-3C.
Time traces of image-error components can be seen in Figure 7 for GSJ on 3C (a) and RC (b) platforms. Big spikes at the vertical dotted lines are target change responses; what matters is how quickly the traces re-enter the dashed band and how well they stay there. In (a) the 3C system overshoots strongly, re-enters, then repeatedly leaks out of the band and creeps. In (b) with redundancy, the step transients are smaller and the traces hug the band afterwards (long, uninterrupted in-band dwell) illustrating the benefit of the extra cables.
Figure 8 contrasts representative MoCap traces from the 3C GSJ controller with the RC controller. In the time plots, the 3C run shows stepped motions followed by clear ringing and small drift on all three axes, whereas the RC run transitions cleanly with little to no bounce and shorter dwell before each flat segment. The top-down XY paths further highlight the difference: 3C arrives through looping, meandering arcs that reflect platform sway, while RC follows a more direct, compact path with minimal lateral wander. The 3D views make the effect on heave and rocking obvious. 3C exhibits small vertical ripples and posture changes as it settles; RC maintains a flatter pose and damps those motions quickly. Overall, the RC configuration reduces oscillation amplitude, cuts jerkiness at step onsets, and limits post-entry jitter, yielding a tighter approach and steadier hold at the target compared to the 3C baseline.
Using MoCap ground truth, we measured the distance between the platform’s optical-center proxy and the nearest predefined target in the horizontal X–Y plane. After the trajectory first entered a 10 mm radius band and dwelled for 0.25 s, we evaluated post-settle accuracy (mean radial error) and residual jitter (RMS of a 0.4 s high-pass). Results are summarized by target in Table 3 and pooled as boxplots in Figure 9a,b. RC reduced post-settle error on most targets (T1: 29 mm vs. 59 mm; T4: 25 mm vs. 36 mm, RC vs. 3C), with T2 the exception where 3C was lower (38 mm vs. 52 mm). Post-settle jitter was comparable across controllers (medians ≈ 7–10 mm). RC also settled more frequently and faster (settle-rate: 0.48–0.73 vs. 0.14–0.71; median t s e t t l e : 1.0–1.3 s vs. 1.1–2.2 s, RC vs. 3C). Notably, 3C failed to produce any settled segments at T3 (median error 117 mm), whereas RC achieved 63 mm (n = 2).

3.2. Redundant Cable Analysis, Moving Target

Moving target (circular trajectory). On the low-speed circular path ( 90 s / r e v ), GSJ maintained lock and tracked on both platforms (5/5 runs) with the median post-lock error 51 mm vs. 153 mm (MoCap), median image error ~20 px vs. 22 px (Table 4), jitter 3 px vs. 11 px as in the static case. In contrast, the ungated RLS failed on 5/5 runs with the 3C platform and succeeded only 2/5 runs with RC; successful RLS-RC runs still exhibited larger image RMS than GSJ. These results are consistent with the failure analysis: when the reference is moving and conditioning dips, the ungated RLS updates on low-SNR residuals and drifts; redundancy raises σ m i n   ( J ) and tempers (but does not eliminate) the issue. (Protocol and metrics as in Section 2.5.)
We computed the Euclidean separation between the platform and the moving target in the horizontal X–Y plane. Lock was declared on first entry into a 10 mm radius with a 1.0 s dwell; post-lock accuracy is the mean radial error, and jitter is the high-pass RMS (0.40 s MA). Table 5 summarizes results across runs. Figure 10 shows boxplots of post-lock mean error (a), and Figure 10 also shows post-lock jitter (b).
Overall, GSJ-RC tracks the moving target substantially closer than GSJ-3C (median post-lock error 51 mm vs. 153 mm), with comparable median jitter (~0.20 mm for RC vs. 0.20 mm for 3C). RLS-RC is inconsistent: despite a small median jitter (0.089 mm), its median post-lock error is large (399 mm) due to multiple runs that never truly converged. 5/5 GSJ-RC and 2/5 RLS-RC runs achieved a formal lock, and 5/5 GSJ-3C runs locked under the 10 mm/1.0 s criterion. This pattern is visible in Figure 10, where RC’s distribution centers lower than 3C, while RLS-RC exhibits heavy-tailed error due to outliers.
In Figure 11a,b we see top-down MoCap traces that show how RC tracks the moving target better. Adding the redundant cables flattens the platform’s static equilibrium and makes the pose stiffer and more isotropic, so image-plane error maps more faithfully to world-frame translation (less tilt-induced parallax and coupling into the camera view). By more isotropic pose, we mean the image Jacobian is better conditioned: its condition number is lower or, equivalently, its smallest singular value is larger. Intuitively, motion is observed with similar gain in all directions, rather than some directions being amplified and others squashed. As a result, the RC trajectory stays near the target ring for the full rotation with smaller bias and lower jitter, while the 3C platform under-tracks and oscillates inside the circle. In short, the RC turns the same image feedback into a more accurate world-space correction and holds the platform steadier throughout the motion. Figure 12 shows the top-down view as well as the MoCap view and live from platform view of the RC platform tracking the moving target.
On moving-target tests the RC configuration achieves comparable lock times but reduces post-lock image-plane jitter by roughly 3 4 × (image-plane, GSJ only) and lowers both median and tail (95th-percentile) image error relative to the 3C setup. These image-plane gains are consistent with RC’s flatter static equilibrium, which reduces platform pose bias and lets the camera track the target trajectory in the world frame more faithfully.
From the controller perspective (image error only), RC tracks the moving target with slightly lower mean error and much lower jitter than 3C once lock is achieved. Table 4 shows the median numbers from the image error perspective. Across the five GSJ runs per setup, the median post-lock mean error is ~19.9 px for RC vs. 22.1 px for 3C, while the 95th-percentile error drops from ~43.6 px (3C) to ~29.6 px (RC). Most notably, the residual/jitter RMS falls from a median of ~10.8 px (3C) to ~3.0 px (RC); as noted earlier about a 3 4 × reduction. Lock times are comparable (medians ≈ 4–5 s), with one RC run locking near-immediately. RLS runs were excluded from the controller-view summary due to unreliable tracking.
Across the moving-target runs, the RC configuration holds the image error substantially steadier than the 3C setup. In RC the platform’s static equilibrium is flatter and better constrained, so the camera pose changes less for the same cable motion. That translates into smaller coupling between platform attitude and the image plane, as seen in Figure 13. Once the target is acquired, ΔU/ΔV remain inside a narrow band with low high-frequency content. By contrast, 3C exhibits slower decay to the band, a persistent bias, and larger oscillations during the full rotation.
Quantitatively (post-lock), RC’s residual/jitter is about 3 px RMS (median across runs) versus ~11 px for 3C, and its p95 image error is consistently lower (typically ~29–37 px for RC vs. ~43–96 px for 3C). Mean radial error is also modestly smaller for RC (≈20 px vs. ~22–24 px), but the biggest benefit is stability. RC keeps the error tightly clustered near zero while 3C shows drift and bursts during motion.

3.3. Failure Mode of RLS

Figure 14a illustrates a representative RLS static target run on the 3C platform. The top panel shows the smallest singular value of the image Jacobian, σ m i n   ( J ) ; shaded bands mark intervals where σ m i n <   J * = 0.03 (poor conditioning). The middle panel plots the RLS Jacobian update magnitude Δ J F with a reference line at τ J   =   0.12 . The bottom panel shows the residual norm r k = e k e k 1 J k q k (log scale). Vertical dotted lines denote step onsets. We observe that extended periods of poor conditioning precede or coincide with large Δ J spikes (e.g., t 0 s, 12 s, 18 s, and 28–29 s), and those spikes are followed by sustained residual growth, indicating model/estimate drift. This example motivates a gated RLS update (enable only when σ m i n >   J * and Δ J F τ J ) and explains why the RC platform, which keeps σ m i n higher, reduces these failures.
To formalize these observations, we define explicit conditions under which RLS updates are likely to diverge. Let Δ q k be the commanded increment, Δ e k the innovation, and J ^ k 1 the current Jacobian estimate. RLS updates are only enabled when all of the following hold:
Δ q k & > ϵ q , ϵ q 2 encoder   counts ,
σ m i n ( J ^ k 1 ) & > ϵ σ , ϵ σ 0.05 px / count ,
R M S ( Δ e k ) σ noise & > ϵ SNR , ϵ SNR 3 .
Equation (16) ensures sufficient excitation so that updates are not dominated by sensor noise. Equation (17) avoids adaptation when the Jacobian is ill-conditioned, preventing large spurious updates. Equation (18) requires residual innovations to exceed the measurement noise floor, avoiding random walk behavior when Δ e k is noise-dominated. Together, these criteria provide testable thresholds for event-triggered adaptation and explain why the RC platform, which maintains higher σ m i n and larger effective excitation, exhibited greater stability. These criteria motivate the event-gated RLS strategies proposed in Section 4.
Figure 14b shows the same diagnostics for an RLS static target run on the RC platform. After a brief start-up period of low conditioning, the smallest singular value of the image Jacobian, σ m i n   ( J ) , remains above the threshold (0.03), indicating a well-conditioned task. The RLS update magnitude Δ J F exhibits only a few transient spikes (near target changes), then quickly returns near zero. The residual norm r k = e k e k 1 J k q k stays bounded and decays after the largest Δ J event, with no runaway growth. Compared to the 3C failure example, the RC configuration maintains higher σ m i n , suppresses large Jacobian updates, and prevents residual blow-up; explaining the higher settle rate and lower post-window error observed in the summary plots.

3.4. Statistical Analysis

Statistical analysis was performed on per-run outcomes (RMS error, settling time, and success rates). We report means with 95% confidence intervals, between-condition comparisons with Welch’s t-test (unequal variances), and standardized effect sizes as Hedges’ g with confidence intervals. For binary outcomes (settle success), Wilson 95% CIs were computed and compared with Fisher’s exact test. Redundancy reduced RMS image error for GSJ (12.3 ± 2.8 px vs. 7.9 ± 1.6 px, p = 0.007, Hedges’ g = 0.85), and similarly for RLS (59.2 ± 7.3 px vs. 31.5 ± 4.8 px, p = 0.002, g = 2.4). Settling times were similar across layouts (GSJ: 2.0 vs. 2.4 s; RLS: 2.3 vs. 3.4 s; differences not statistically significant). RC also reduced jitter, consistent with its stabilizing effect on tilt and pose drift. Settle success was near 100% for GSJ in both layouts. For RLS, success improved from 0.43 [0.16–0.75] in 3C to 0.67 [0.44–0.84] in RC (Fisher’s p = 0.38). Although not statistically significant at n < 20, the trend supports redundancy as a stabilizing factor for ungated RLS.

4. Discussion

Our results are for a single monocular camera regulating a 2-DoF image point, which under-actuates the platform dynamics; behaviors may differ with multi-feature or pose-based IBVS. The settle-band criteria (±20 px GSJ, ±22 px RLS) and short dwell were chosen to match the controllers’ intended operation; different bands would shift reported settle rates but not the qualitative 3C↔RC trends we observe. The RLS implementation was deliberately ungated and lightly regularized to expose failure modes; event-triggered updates or stronger regularization would likely improve robustness (and will be the focus of future work). We did not sense cable tensions, so unmodeled elasticity and backlash enter as disturbances; closed-loop force feedback could further reduce residual error. Finally, our tests used a single system and controller gains; while we varied targets and repeated runs, broader hardware and gain sweeps would strengthen external validity.
A natural question is how these uncalibrated baselines compare to calibrated visual servoing (CVS) or other adaptive schemes. Such benchmarks require calibrated kinematic and camera models and separate controller implementations, which were beyond the scope of this initial study. Our aim here was to establish a calibration-free baseline for spatial CDPRs, consistent with how UVS has been evaluated for serial manipulators. Future work will extend the comparison set to include vs. and alternative adaptive strategies, enabling a fuller picture of trade-offs between calibration effort, robustness, and performance. Comparing image-based UVS to calibration-based visual servoing is a valuable next step; here we isolate calibration-free performance.
Dual-cable redundancy made the platform mechanically stiffer, which suppressed roll and pitch motion and reduced tilt or drift of the platform. With this extra stiffness, the camera remained closer to level, so image errors corresponded more directly to actual platform displacements. As a result, the redundant setup tracked targets more faithfully, settled with less overshoot, and exhibited less jitter. This same effect also explains why the RLS estimator behaved more stably in RC: because the platform tilted less, the feature motions it observed were cleaner and more consistent, leading to smoother parameter updates rather than the occasional unstable spikes seen in 3C (see Figure 14).
The single-camera, eye-in-hand configuration also imposes an observability limitation. With only one monocular view, depth must be inferred indirectly through motion or model assumptions, which restricts robustness compared to stereo or anchor-mounted multi-view setups that could provide direct depth information. Likewise, our trajectory set was limited to a fixed circular path. This speed was chosen deliberately to isolate controller behavior under quasi-static conditions. More complex trajectories were not available on the current platform but represent an important direction for future experiments. Multi-view sensing and richer trajectory libraries would both strengthen robustness tests and clarify the boundaries where GSJ remains adequate versus where adaptive methods become necessary.
Our results address three questions about UVS on spatial CDPRs: when a fixed image Jacobian (GSJ) suffices, how mechanical redundancy affects closed-loop behavior, and where an online Jacobian (RLS) helps or fails. First, the RC platform (redundant per-corner cable pairs) consistently improved conditioning, reflected in higher σ m i n   ( J ) , lower oscillation, and tighter steady behavior, relative to the 3C platform. In that better-conditioned regime, GSJ delivered reliable tracking on both static and moving targets with lower post-settle/world-space error and comparable or smaller image-plane jitter than 3C, and with settle rates 0.48–0.73 vs. 0.14–0.71, and median settle times 1.0–1.3 s vs. 1.1–2.2 s. These findings support the working hypothesis that, under adequate conditioning, a carefully estimated fixed mapping from pixels to motors is sufficient for accurate UVS without full geometric calibration. They also show that simple mechanical changes (redundant cables) can be more impactful than increasing algorithmic complexity.
Second, we examined RLS fairly and in context. RLS did provide benefit when the run offered sufficient excitation and the Jacobian remained well conditioned, but outside that envelope it frequently amplified noise, produced large residuals, and exhibited failure modes on the moving-target task (like divergence under low excitation or near-singular J ). This aligns with prior intuition: single-view UVS on a spatial CDPR is strongly nonlinear, with depth/pose coupling and internal platform modes (roll/pitch) that a local linear RLS model cannot robustly absorb without safeguards. The clear implication is not that RLS is ineffective, but that it must be deployed with (i) excitation scheduling, (ii) strong regularization, and (iii) a supervisor that prevents updates when the information geometry is poor. Concretely, event-triggered adaptation using gates on σ m i n   ( J ) , a bounded update norm J F , and residual magnitude can prevent noise-driven changes; robust losses (like Huber [33]) and directional or covariance-reset forgetting can stabilize estimates; and confidence-weighted blending J = α J R L S + ( 1 α ) J G S J with α tied to these gates can retain GSJ reliability while exploiting learnable structure when safe.
Third, the sensing/actuation coupling deserves emphasis. With a body-mounted monocular camera, platform attitude changes modulate the image Jacobian and degrade observability; this was most visible on the under-constrained 3C platform and on moving-target trajectories. A pragmatic remedy is to decouple perception from platform attitude via a nadir-stabilized camera (passive gravity gimbal or active two-axis pitch/roll gimbal). Maintaining a near-nadir view flattens the mapping from world translations to image motion, raises σ m i n   ( J ) , and improves the signal-to-noise ratio of the residual; conditions under which both GSJ and RLS operate more predictably. Keeping the camera near-nadir reduces perspective foreshortening and roll/pitch coupling, so world x–y translations produce more uniform, linear pixel shifts. This improves Jacobian conditioning and increases the residual signal-to-noise ratio, under which both GSJ and RLS behave more predictably. In the same spirit, multi-view sensing or lightweight depth cues would further linearize the mapping and reduce reliance on platform pose to reduce camera-frame jitter.
Broader implications are twofold. For practitioners seeking robust, low-tuning UVS on spatial CDPRs, invest first in mechanical conditioning (redundant cables or equivalent stiffness/layout changes) and perception decoupling (nadir-stabilized camera). In that envelope, a fixed GSJ is a strong baseline that meets accuracy and settling requirements without the brittleness of adaptation. For applications with evolving workspaces or payloads where J genuinely changes, RLS (or more expressive Jacobian models) remains attractive, but only with excitation management and safety supervision as above.
Limitations include single-camera sensing and a laboratory trajectory set; also, our jitter metric (high-pass RMS after dwell) captures residual motion but not all perceptual artifacts (such as blur). Future research should: (1) formalize the adaptation supervisor with provable bounds and auto-tuned gates; (2) explore richer, scheduled micro-excitation that is persistently exciting yet visually unobtrusive; (3) test nadir-stabilized or gimbal-mounted cameras and quantify their effect on σ m i n   ( J ) , residuals, and tracking; (4) extend to multi-view or visual-inertial sensing to break single-view degeneracies; and (5) compare fixed- J , RLS, and hybrid/confidence-weighted controllers across broader tasks and payloads. Taken together, the evidence suggests a pragmatic path: fix the physics (conditioning and viewpoint), then add adaptation sparingly and safely where it truly buys invariance. Additionally, in this study, we passed moving-averaged image coordinates into the RLS update to suppress sensor noise. While this improves numerical conditioning, it deviates from the standard RLS assumption of single-sample updates and may bias adaptation. Future work will analyze this effect explicitly or remove pre-filtering to ensure algorithmic consistency.

5. Conclusions

We evaluated uncalibrated visual servoing (UVS) on spatial CDPRs by contrasting a global static Jacobian (GSJ) with an online RLS update across 3C and redundant RC platforms. Redundancy improved conditioning ( σ m i n ( J ) ), reduced oscillation, and increased settle success. On both static and moving tasks, GSJ was the most reliable controller, achieving tighter tracking and lower residuals, while ungated RLS diverged when excitation was weak or conditioning was poor. These findings indicate that, for single-camera UVS on spatial CDPRs, mechanical conditioning can be more impactful than basic online adaptation, and a carefully estimated GSJ may suffice for quasi-static motions on well-conditioned platforms. Practically, if adaptation is retained, it should be event-triggered using gates on σ m i n ( J ) , Δ J F , and residual magnitude. Limitations include single-camera sensing, slow laboratory trajectories, and an ungated RLS variant; future work should test multi-view sensing, faster trajectories, and comparisons with CVS and other adaptive schemes.

Author Contributions

Conceptualization, J.-S.K.J.; methodology, J.-S.K.J.; software, J.-S.K.J.; validation, J.-S.K.J.; formal analysis, J.-S.K.J.; investigation, J.-S.K.J.; resources, J.-S.K.J.; data curation, J.-S.K.J.; writing—original draft preparation, J.-S.K.J.; writing—review and editing, M.M.; visualization, J.-S.K.J.; supervision, M.M. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Data Availability Statement

The raw data supporting the conclusions of this article will be made available by the authors on request.

Acknowledgments

This article builds off of and expands on a paper entitled “Control of Cable-Driven Parallel Robots Using Uncalibrated Visual Servoing,” which was presented at the 2025 IEEE International Conference on Omni-layer Intelligent Systems (COINS), Madison, Wisconsin, USA, 4–6 August 2025 [32]. This article builds off of and expands on a paper entitled “Uncalibrated Visual Servoing With Recursive Least Squares: Adaptive Control for Cable-Driven Parallel Robots,” which was presented at the 22nd International Conference on Ubiquitous Robots (UR), College Station, TX, USA, 30 June–2 July 2025 [29].

Conflicts of Interest

The authors declare no conflict of interest.

Abbreviations

The following abbreviations are used in this manuscript:
3CThree-cable, single-plane CDPR platform
CDPRCable-Driven Parallel Robot
CVSCalibrated Visual Servoing
ECDFEmpirical Cumulative Distribution Function
FFForgetting Factor
GSJGlobal Static Jacobian
HP-MAHigh-Pass via Moving-Average subtraction
IEImage Error
MAMoving Average
MoCapMotion capture
p9595th percentile
RCRedundant-cable platform
RLSRecursive Least Squares
RMSERoot-Mean-Square Error
RMSRoot-Mean-Square
SNRSignal-to-Noise Ratio
SVDSingular Value Decomposition
TSVDTruncated Singular Value Decomposition
UVSUncalibrated Visual Servoing

References

  1. Zake, Z.; Chaumette, F.; Pedemonte, N.; Caro, S. Robust 2½D Visual Servoing of A Cable-Driven Parallel Robot Thanks to Trajectory Tracking. IEEE Robot. Autom. Lett. 2020, 5, 660–667. [Google Scholar] [CrossRef]
  2. Idà, E.; Mattioni, V. Cable-Driven Parallel Robot Actuators: State of the Art and Novel Servo-Winch Concept. Actuators 2022, 11, 290. [Google Scholar] [CrossRef]
  3. Zare, S.; Ghanatian, M.; Hairi Yazdi, M.R.; Tale Masouleh, M. Reconstructing 3-D Graphical Model Using an Under-Constrained Cable-Driven Parallel Robot. In Proceedings of the 2020 6th Iranian Conference on Signal Processing and Intelligent Systems (ICSPIS), Mashhad, Iran, 23–24 December 2020; pp. 1–6. [Google Scholar]
  4. Kawamura, S.; Choe, W.; Tanaka, S.; Pandian, S.R. Development of an Ultrahigh Speed Robot FALCON Using Wire Drive System. In Proceedings of the 1995 IEEE International Conference on Robotics and Automation, Nagoya, Japan, 21–27 May 1995; Volume 1, pp. 215–220. [Google Scholar]
  5. Lamaury, J.; Gouttefarde, M. Control of a Large Redundantly Actuated Cable-Suspended Parallel Robot. In Proceedings of the 2013 IEEE International Conference on Robotics and Automation, Karlsruhe, Germany, 6–10 May 2013; pp. 4659–4664. [Google Scholar]
  6. Izard, J.-B.; Gouttefarde, M.; Michelin, M.; Tempier, O.; Baradat, C. A Reconfigurable Robot for Cable-Driven Parallel Robotic Research and Industrial Scenario Proofing. In Cable-Driven Parallel Robots; Mechanisms and Machine Science; Bruckmann, T., Pott, A., Eds.; Springer: Berlin/Heidelberg, Germany, 2013; Volume 12, pp. 135–148. ISBN 978-3-642-31987-7. [Google Scholar]
  7. Schmidt, V.L. Modeling Techniques and Reliable Real-Time Implementation of Kinematics for Cable-Driven Parallel Robots Using Polymer Fiber Cables; Universität Stuttgart: Stuttgart, Germany, 2017. [Google Scholar]
  8. Picard, É.; Caro, S.; Claveau, F.; Plestan, F. Pulleys and Force Sensors Influence on Payload Estimation of Cable-Driven Parallel Robots. In Proceedings of the 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 1–5 October 2018; pp. 1429–1436. [Google Scholar]
  9. Dallej, T.; Gouttefarde, M.; Andreff, N.; Dahmouche, R.; Martinet, P. Vision-Based Modeling and Control of Large-Dimension Cable-Driven Parallel Robots. In Proceedings of the 2012 IEEE/RSJ International Conference on Intelligent Robots and Systems, Algarve, Portugal, 7–12 October 2012; pp. 1581–1586. [Google Scholar]
  10. Zake, Z.; Chaumette, F.; Pedemonte, N.; Caro, S. Visual Servoing of Cable-Driven Parallel Robots with Tension Management. In Proceedings of the 2021 IEEE International Conference on Robotics and Automation (ICRA), Xi’an, China, 30 May–5 June 2021; pp. 6861–6867. [Google Scholar]
  11. Dallej, T.; Gouttefarde, M.; Andreff, N.; Michelin, M.; Martinet, P. Towards vision-based control of cable-driven parallel robots. In Proceedings of the Towards Vision-Based Control of Cable-Driven Parallel Robots, San Francisco, CA, USA, 25–30 September 2011. [Google Scholar]
  12. Ramadour, R.; Chaumette, F.; Merlet, J.-P. Grasping Objects with a Cable-Driven Parallel Robot Designed for Transfer Operation by Visual Servoing. In Proceedings of the 2014 IEEE International Conference on Robotics and Automation (ICRA), Hong Kong, China, 31 May–7 June 2014; pp. 4463–4468. [Google Scholar]
  13. Gabaldo, S.; Idà, E.; Carricato, M. Pose-Estimation Methods for Underactuated Cable-Driven Parallel Robots. Mech. Mach. Theory 2024, 199, 105690. [Google Scholar] [CrossRef]
  14. Carricato, M.; Merlet, J.-P. Stability Analysis of Underconstrained Cable-Driven Parallel Robots. IEEE Trans. Robot. 2013, 29, 288–296. [Google Scholar] [CrossRef]
  15. Awais, M.; Park, J.-H.; Jung, J.; Choi, E.-P.; Park, J.-O.; Kim, C.-S. Real-Time Vision-Based Localization of Planar Cable-Driven Parallel Robot. In Proceedings of the 2018 18th International Conference on Control, Automation and Systems (ICCAS), PyeongChang, Republic of Korea, 17–20 October 2018; pp. 462–465. [Google Scholar]
  16. Tremblay, N.; Kamali, K.; Cardou, P.; Desrosiers, C.; Gouttefarde, M.; Otis, M.J.-D. Eye-on-Hand Calibration Method for Cable-Driven Parallel Robots. In Cable-Driven Parallel Robots; Mechanisms and Machine Science; Pott, A., Bruckmann, T., Eds.; Springer International Publishing: Cham, Switzerland, 2019; Volume 74, pp. 345–356. ISBN 978-3-030-20750-2. [Google Scholar]
  17. Borgstrom, P.H.; Jordan, B.L.; Borgstrom, B.J.; Stealey, M.J.; Sukhatme, G.S.; Batalin, M.A.; Kaiser, W.J. NIMS-PL: A Cable-Driven Robot With Self-Calibration Capabilities. IEEE Trans. Robot. 2009, 25, 1005–1015. [Google Scholar] [CrossRef]
  18. Idá, E.; Merlet, J.-P.; Carricato, M. Automatic Self-Calibration of Suspended Under-Actuated Cable-Driven Parallel Robot Using Incremental Measurements. In Cable-Driven Parallel Robots; Mechanisms and Machine Science; Pott, A., Bruckmann, T., Eds.; Springer International Publishing: Cham, Switzerland, 2019; Volume 74, pp. 333–344. ISBN 978-3-030-20750-2. [Google Scholar]
  19. dit Sandretto, J.A.; Daney, D.; Gouttefarde, M. Calibration of a Fully-Constrained Parallel Cable-Driven Robot. In Proceedings of the Romansy 19—Robot Design, Dynamics and Control, Paris, France, 12–14 June 2012; Padois, V., Bidaud, P., Khatib, O., Eds.; Springer: Vienna, Austria, 2013; pp. 77–84. [Google Scholar]
  20. Fortin-Côté, A.; Cardou, P.; Gosselin, C. An Admittance Control Scheme for Haptic Interfaces Based on Cable-Driven Parallel Mechanisms. In Proceedings of the 2014 IEEE International Conference on Robotics and Automation (ICRA), Hong Kong, China, 31 May–7 June 2014; pp. 819–825. [Google Scholar]
  21. Idà, E.; Briot, S.; Carricato, M. Robust Trajectory Planning of Under-Actuated Cable-Driven Parallel Robot with 3 Cables. In Proceedings of the Advances in Robot Kinematics 2020, Ljubljana, Slovenia, 28 June–2 July 2020; Lenarčič, J., Siciliano, B., Eds.; Springer International Publishing: Cham, Switzerland, 2021; pp. 65–72. [Google Scholar]
  22. Wang, H.; Jiang, M.; Chen, W.; Liu, Y.-H. Visual Servoing of Robots with Uncalibrated Robot and Camera Parameters. Mechatronics 2012, 22, 661–668. [Google Scholar] [CrossRef]
  23. Armstrong Piepmeier, J.; McMurray, G.V.; Lipkin, H. A Dynamic Jacobian Estimation Method for Uncalibrated Visual Servoing. In Proceedings of the 1999 IEEE/ASME International Conference on Advanced Intelligent Mechatronics (Cat. No.99TH8399), Atlanta, GA, USA, 19–23 September 1999; pp. 944–949. [Google Scholar]
  24. Zake, Z.; Caro, S.; Roos, A.S.; Chaumette, F.; Pedemonte, N. Stability Analysis of Pose-Based Visual Servoing Control of Cable-Driven Parallel Robots. In Proceedings of the Cable-Driven Parallel Robots, Krakow, Poland, 30 June–4 July 2019; Springer International Publishing: Cham, Switzerland, 2019; pp. 73–84. [Google Scholar]
  25. Santamaria-Navarro, À.; Andrade-Cetto, J. Uncalibrated Image-Based Visual Servoing. In Proceedings of the 2013 IEEE International Conference on Robotics and Automation, Karlsruhe, Germany, 6–10 May 2013; pp. 5247–5252. [Google Scholar]
  26. Jagersand, M.; Fuentes, O.; Nelson, R. Experimental Evaluation of Uncalibrated Visual Servoing for Precision Manipulation. In Proceedings of the International Conference on Robotics and Automation, Albuquerque, NM, USA, 20–25 April 1997; IEEE: Albuquerque, NM, USA, 1997; Volume 4, pp. 2874–2880. [Google Scholar]
  27. Piepmeier, J.A.; McMurray, G.V.; Lipkin, H. Experimental Results Using Vision-Based Control for Uncalibrated Robotic Systems. In Proceedings of the Intelligent Robots and Computer Vision XVIII: Algorithms, Techniques, and Active Vision, Boston, MA, USA, 20–21 September 1999; SPIE: Bellingham, WA, USA, 1999; Volume 3837, pp. 98–107. [Google Scholar]
  28. Espiau, B.; Chaumette, F.; Rives, P. A New Approach to Visual Servoing in Robotics. IEEE Trans. Robot. Autom. 1992, 8, 313–326. [Google Scholar] [CrossRef]
  29. Jenny, J.-S.K.; Marshall, M. Uncalibrated Visual Servoing With Recursive Least Squares: Adaptive Control for Cable-Driven Parallel Robots. In Proceedings of the 2025 22nd International Conference on Ubiquitous Robots (UR), College Station, TX, USA, 30 June–2 July 2025; pp. 6–12. [Google Scholar]
  30. Malis, E.; Chaumette, F.; Boudet, S. 2 1/2 D Visual Servoing. IEEE Trans. Robot. Autom. 1999, 15, 238–250. [Google Scholar] [CrossRef]
  31. Armstrong Piepmeier, J.; McMurray, G.V.; Lipkin, H. A Dynamic Quasi-Newton Method for Uncalibrated Visual Servoing. In Proceedings of the 1999 IEEE International Conference on Robotics and Automation (Cat. No.99CH36288C), Atlanta, GA, USA, 19–23 May 1999; Volume 2, pp. 1595–1600. [Google Scholar]
  32. Jenny, J.-S.K.; Marshall, M. Control of Cable-Driven Parallel Robots Using Uncalibrated Visual Servoing. In Proceedings of the 2025 IEEE International Conference on Omni-Layer Intelligent Systems (COINS), Madison, WI, USA, 4–6 August 2025; pp. 1–7. [Google Scholar]
  33. Huber, P.J. Robust Estimation of a Location Parameter. In Breakthroughs in Statistics: Methodology and Distribution; Kotz, S., Johnson, N.L., Eds.; Springer: New York, NY, USA, 1992; pp. 492–518. ISBN 978-1-4612-4380-9. [Google Scholar]
Figure 1. Redundant cable layout (RC) with dual-cable anchors at each corner. Red lines denote the cables, with each pair acting like a parallel spring to increase stiffness, reduce platform tilt, and provide more consistent image-plane behavior.
Figure 1. Redundant cable layout (RC) with dual-cable anchors at each corner. Red lines denote the cables, with each pair acting like a parallel spring to increase stiffness, reduce platform tilt, and provide more consistent image-plane behavior.
Applsci 15 10144 g001
Figure 2. Experimental platforms. (a) Three-cable (3C) under-constrained CDPR setup with a single cable attached at each corner of the moving platform. (b) Redundant-cable (RC) dual-plane setup with paired cables per corner, increasing stiffness and conditioning.
Figure 2. Experimental platforms. (a) Three-cable (3C) under-constrained CDPR setup with a single cable attached at each corner of the moving platform. (b) Redundant-cable (RC) dual-plane setup with paired cables per corner, increasing stiffness and conditioning.
Applsci 15 10144 g002
Figure 3. Visual-servo control loop used in this work (camera feed → image error → TSVD pseudo-inverse → command increment → plant).
Figure 3. Visual-servo control loop used in this work (camera feed → image error → TSVD pseudo-inverse → command increment → plant).
Applsci 15 10144 g003
Figure 4. Conditioning versus disturbance residual. (a) Full scale highlights rare, very large residual spikes that occur at very poor conditioning and are associated with RLS. (b) Zoomed to 0–15 px shows the main cloud: GSJ remains compact at high conditioning with lower spread in residuals; RLS improves with RC (points shift right/down) but still exhibits broader variation than GSJ. Overall, better conditioning tends to coincide with smaller residuals (bottom-right is optimal).
Figure 4. Conditioning versus disturbance residual. (a) Full scale highlights rare, very large residual spikes that occur at very poor conditioning and are associated with RLS. (b) Zoomed to 0–15 px shows the main cloud: GSJ remains compact at high conditioning with lower spread in residuals; RLS improves with RC (points shift right/down) but still exhibits broader variation than GSJ. Overall, better conditioning tends to coincide with smaller residuals (bottom-right is optimal).
Applsci 15 10144 g004
Figure 5. Conditioning distributions (boxplot). Each box summarizes the distribution of conditioning values ( σ m i n ) across segments. Boxes show interquartile ranges, whiskers show the data spread, and the orange line marks the median.
Figure 5. Conditioning distributions (boxplot). Each box summarizes the distribution of conditioning values ( σ m i n ) across segments. Boxes show interquartile ranges, whiskers show the data spread, and the orange line marks the median.
Applsci 15 10144 g005
Figure 6. Post-window image-error RMS by controller and cable configuration (boxplot). The orange line inside each box indicates the median RMS value; boxes show the interquartile range; whiskers denote the spread of non-outlier values. Outliers are plotted individually; numeric labels correspond to specific outlier runs.
Figure 6. Post-window image-error RMS by controller and cable configuration (boxplot). The orange line inside each box indicates the median RMS value; boxes show the interquartile range; whiskers denote the spread of non-outlier values. Outliers are plotted individually; numeric labels correspond to specific outlier runs.
Applsci 15 10144 g006
Figure 7. The RC platform (b), GSJ controller shown, reduces axis-coupled overshoot and increases in-band dwell compared to 3C (a). After the first band entry, the RC platform holds nearly all subsequent samples within ±20 px, while the 3C platform shows repeated exits and a slow creep. Vertical dotted lines mark responses to target changes; traces show responses to those target changes.
Figure 7. The RC platform (b), GSJ controller shown, reduces axis-coupled overshoot and increases in-band dwell compared to 3C (a). After the first band entry, the RC platform holds nearly all subsequent samples within ±20 px, while the 3C platform shows repeated exits and a slow creep. Vertical dotted lines mark responses to target changes; traces show responses to those target changes.
Applsci 15 10144 g007
Figure 8. MoCap comparison of 3C GSJ (a,c,e,g,i) vs. RC (b,d,f,h,j). Time traces of X (a,b), Y (c,d), Z (e,f) and the corresponding overhead XY (g,f), and the 3D paths (i,j) show that RC produces a smoother approach with smaller oscillations, less sway, and steadier final hold.
Figure 8. MoCap comparison of 3C GSJ (a,c,e,g,i) vs. RC (b,d,f,h,j). Time traces of X (a,b), Y (c,d), Z (e,f) and the corresponding overhead XY (g,f), and the 3D paths (i,j) show that RC produces a smoother approach with smaller oscillations, less sway, and steadier final hold.
Applsci 15 10144 g008
Figure 9. (a) Residual jitter after settle (mm). (b) Accuracy after settle (mm). This is across both controllers. Boxplots show the interquartile range (box), whiskers (1.5 × IQR), and outliers (points). The orange line indicates the median value within each distribution. Results show that redundant cabling (RC) tends to reduce both residual jitter and post-settle radial error compared to the under-constrained 3C platform.
Figure 9. (a) Residual jitter after settle (mm). (b) Accuracy after settle (mm). This is across both controllers. Boxplots show the interquartile range (box), whiskers (1.5 × IQR), and outliers (points). The orange line indicates the median value within each distribution. Results show that redundant cabling (RC) tends to reduce both residual jitter and post-settle radial error compared to the under-constrained 3C platform.
Applsci 15 10144 g009
Figure 10. (a) Moving-target accuracy (world X–Y). Post-lock mean radial error (mm) for each configuration. Lock = first entry into a 10 mm band with a 1.0 s dwell. GSJ-RC shows the lowest errors; GSJ-3C is higher; RLS-RC is large and variable (only 2/5 runs locked; others failed). (b) Moving-target jitter (world X–Y). Post-lock high-pass RMS (0.4 s MA) of the platform-to-target error. Sub-mm jitter is similar for GSJ-3C and GSJ-RC (~0.2 mm median); RLS-RC is comparable in the runs that locked. Arrows mark outliers beyond the axis limits.
Figure 10. (a) Moving-target accuracy (world X–Y). Post-lock mean radial error (mm) for each configuration. Lock = first entry into a 10 mm band with a 1.0 s dwell. GSJ-RC shows the lowest errors; GSJ-3C is higher; RLS-RC is large and variable (only 2/5 runs locked; others failed). (b) Moving-target jitter (world X–Y). Post-lock high-pass RMS (0.4 s MA) of the platform-to-target error. Sub-mm jitter is similar for GSJ-3C and GSJ-RC (~0.2 mm median); RLS-RC is comparable in the runs that locked. Arrows mark outliers beyond the axis limits.
Applsci 15 10144 g010
Figure 11. (a) GSJ-3C: Platform path (orange) rides well inside the moving target trajectory (blue) due to pose to image-plane offset (offset between MoCap pose of the camera optical center and the target’s projection that produces the observed pixel error) and oscillates during motion. (b) GSJ-RC: Platform path closely hugs the moving target trajectory with visibly less oscillations.
Figure 11. (a) GSJ-3C: Platform path (orange) rides well inside the moving target trajectory (blue) due to pose to image-plane offset (offset between MoCap pose of the camera optical center and the target’s projection that produces the observed pixel error) and oscillates during motion. (b) GSJ-RC: Platform path closely hugs the moving target trajectory with visibly less oscillations.
Applsci 15 10144 g011
Figure 12. Experimental data from the redundant-cable (RC) platform tracking a moving target: (a) Overhead view of the RC platform during a moving-target run. (b) Corresponding motion-capture (MoCap) data showing trajectories: yellow = RC platform, green = moving target. (c) Live image feed from the onboard camera used for UVS, showing target features tracked in real time.
Figure 12. Experimental data from the redundant-cable (RC) platform tracking a moving target: (a) Overhead view of the RC platform during a moving-target run. (b) Corresponding motion-capture (MoCap) data showing trajectories: yellow = RC platform, green = moving target. (c) Live image feed from the onboard camera used for UVS, showing target features tracked in real time.
Applsci 15 10144 g012
Figure 13. (a) GSJ–3C, moving target: ΔU and ΔV vs. time with ±20 px band. After lock, the image error drifts and oscillates, with sustained bias in both axes. (b) GSJ–RC, moving target: ΔU and ΔV vs. time with ±20 px band. Faster lock and tighter regulation; error stays close to zero with noticeably lower jitter.
Figure 13. (a) GSJ–3C, moving target: ΔU and ΔV vs. time with ±20 px band. After lock, the image error drifts and oscillates, with sustained bias in both axes. (b) GSJ–RC, moving target: ΔU and ΔV vs. time with ±20 px band. Faster lock and tighter regulation; error stays close to zero with noticeably lower jitter.
Applsci 15 10144 g013
Figure 14. RLS diagnostics on 3C vs. RC platforms. Each subplot shows (top) a conditioning index (minimum singular value of the image Jacobian) with low-conditioning regions shaded, (middle) the size of the RLS Jacobian update with large spikes highlighted, and (bottom) the model-mismatch residual on a log scale; dotted lines mark step times. (a) 3C: extended poor conditioning precedes repeated large updates and residual growth. (b) RC: conditioning stays high, update spikes are brief, and the residual remains bounded.
Figure 14. RLS diagnostics on 3C vs. RC platforms. Each subplot shows (top) a conditioning index (minimum singular value of the image Jacobian) with low-conditioning regions shaded, (middle) the size of the RLS Jacobian update with large spikes highlighted, and (bottom) the model-mismatch residual on a log scale; dotted lines mark step times. (a) 3C: extended poor conditioning precedes repeated large updates and residual growth. (b) RC: conditioning stays high, update spikes are brief, and the residual remains bounded.
Applsci 15 10144 g014
Table 1. Default values and practical ranges (for reproducibility).
Table 1. Default values and practical ranges (for reproducibility).
ItemSymbolTypical Setting
Control rate25–200 Hz (match your loop)
Image low-pass2–3 Hz, zero-phase (or 3–5 sample MA)
Per-motor increment cap | Δ q | m a x 2–5 counts/cycle (tune for smoothness)
GSJ regularizer γ 10 2   ( tune   10 3 10 1 )
RLS forgetting λ 0.98–0.995 (0.98 in our logs)
RLS covariance init P 0 α I ,   α = 10 3 10 4
Velocity estimation central   difference   + same LPF as image
Table 2. Effect of redundancy (static target).
Table 2. Effect of redundancy (static target).
PlatformController t s e t t l e Median (s)Post-RMS Median (px)Residual Median (px)
3C: 3-Cable
Single Plane
GSJ2.0012.315.89
RLS2.3059.174.18
RC: Redundant
Dual Plane
GSJ2.448.204.18
RLS3.3831.524.65
Table 3. Per-target MoCap accuracy and jitter (medians).
Table 3. Per-target MoCap accuracy and jitter (medians).
PlatformTargetMedian Mean Error (mm)IQR Mean Error (mm)Median Jitter RMS (mm)IQR Jitter RMS (mm)Settle RateMedian
t s e t t l e (s)
3CT159.43812.7713.820.1432.205
3CT237.5654.287.304.560.5241.06
3CT3117.1613.7611.800.710.000
3CT435.5457.497.635.220.7061.51
RCT129.2448.139.23.460.6921.00
RCT252.0051.048.698.710.4760.96
RCT363.3535.706.171.120.5000.94
RCT425.0235.798.013.650.7331.32
Table 4. Moving-target Image-plane summary by setup.
Table 4. Moving-target Image-plane summary by setup.
SetupMedian Lock
(s)
Median Mean
Err (px)
Median p95 Err
(px)
Median Residual
RMS (px)
3C4.0822.143.610.8
RC4.5219.929.63.0
Table 5. Moving-target MoCap summary by setup.
Table 5. Moving-target MoCap summary by setup.
LabelComplete RunsPost-Lock Error (mm)—
Mean/Median
Post-Lock Jitter RMS (mm)—
Mean/Median
GSJ-3C5/5154.5/153.40.26/0.199
GSJ-RC5/555.2/51.41.71/0.202
RLS-RC2/5353.8/398.92.13/0.089
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Jenny, J.-S.K.; Marshall, M. Uncalibrated Visual Servoing for Spatial Under-Constrained Cable-Driven Parallel Robots. Appl. Sci. 2025, 15, 10144. https://doi.org/10.3390/app151810144

AMA Style

Jenny J-SK, Marshall M. Uncalibrated Visual Servoing for Spatial Under-Constrained Cable-Driven Parallel Robots. Applied Sciences. 2025; 15(18):10144. https://doi.org/10.3390/app151810144

Chicago/Turabian Style

Jenny, Jarrett-Scott K., and Matt Marshall. 2025. "Uncalibrated Visual Servoing for Spatial Under-Constrained Cable-Driven Parallel Robots" Applied Sciences 15, no. 18: 10144. https://doi.org/10.3390/app151810144

APA Style

Jenny, J.-S. K., & Marshall, M. (2025). Uncalibrated Visual Servoing for Spatial Under-Constrained Cable-Driven Parallel Robots. Applied Sciences, 15(18), 10144. https://doi.org/10.3390/app151810144

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop