Keywords

1 Introduction

Within many areas of industry, people put their lives at risk while working in hazardous environments such as nuclear waste decommission, disaster response and explosive ordinance disposal. Environments such as these have given rise to one of the driving factors behind recent innovation within the field of robotics; replacing humans with robots in these environments, mitigating risk to human lives. The quadrupedal legged manipulator shows great potential for this application due to its proficiency in traversing over rough terrain and its ability to interact with its environment. However, these robots are highly redundant systems and therefore require an effective control framework to utilise this redundancy. The favoured method within research of maximising the efficiency of these robots is whole-body control (WBC) through optimisation as this method is able to leverage this high redundancy to achieve multiple tasks simultaneously, with all elements of the robot working cooperatively.

Fig. 1.
figure 1

System overview of the teleoperated legged manipulator.

In the literature, WBC frameworks are normally formulated as either an inverse dynamics (ID) [6, 13, 18] or an inverse kinematics (IK) [2, 7, 19] based optimisation problem. An ID-based WBC framework, utilising a weighted QP problem, is developed in [18] and paired with model predictive control (MPC) for humanoid locomotion. This WBC-MPC pairing is also utilised in [13] to enable quadrupedal legged manipulator to execute a range of gaits and manipulation tasks by optimising for joint torques. To improve control over how tasks are realised by these WBCs for whole-body motion tracking, [6] produced an advanced task prioritisation method. These types of frameworks offer impressive results in tackling real-world obstacles, such as spring-loaded doors [9]. While joint level torque control is not possible, IK-based WBC frameworks are preferable for position-controlled robots. An IK-based WBC is developed in [2] which ensures the stability of wheeled quadruped robots, although it has not been tested while completing a gait. To enhance the robustness of IK-based WBCs, [7] introduces specialised adaptability tasks, but its proficiency is dependent on wheeled locomotion. In the effort of improving the safety of humanoid robots, a generic WBC framework is designed in [19] for collision avoidance, however, it has yet to be expanded for use in robots with five limbs.

Moreover, jobs in hazardous environments are typically too complex for robots to autonomously perform. Therefore, robust and effective teleoperation controllers have been developed for real-life scenarios. Motion capture suits have been seen previously to control robots, such as in [5], but not in such an application where direct joint mapping is not optimal. IMU-based motion capture devices have been used to control a 7 Degree-of-Freedom (DoF) robotic arm [17]. The use of foot position and stance estimation tracking of the teleoperator allows a bipedal robot to mimic walking action [8], though walking delays arose due to imperfect motion recognition.

It is natural to combine WBC and teleoperation strategies together to give people more control authority over the robot, as complex tasks in hazardous environments require redundant whole-body motions and prompt human interventions. An aerial manipulator was controlled using a WBC teleoperation framework designed for use in scenarios with input delay and connection issues [3], however, using a joystick to align the robot with an object makes teleoperation more difficult. A wheeled manipulator was teleoperated through the use of a 3D motion tracking device and monitoring the teleoperator’s muscle activity [15]. The robot is however limited to wheeled locomotion, decreasing the overall mobility of the system. Two control methods are shown utilising both joysticks and a wearable motion capture suit for the low- and high-level control of a bipedal robot [12], however, this method can only be used for robots that are kinematically similar to humans. A teleoperation system is described through the use of a haptic feedback device to control the arms of a bipedal robot [1]. The system, however, does not allow the robot to locomote with the use of gaits. The whole-body motion capture suit with an IK retargeting method is shown in [5] to control multiple humanoid robots, but the centre of mass (CoM) trajectories cannot be directly controlled through this method, limiting its functionality. A joystick-controlled quadrupedal robot is shown to use WBC to perform basic manipulation and depth sensing tasks [16]. Xsens body sensors were used in the WBC of a simulated bipedal robot with direct kinematic mapping between the teleoperator and robot [4], however, strategies that could improve teleoperation such as fixing a robot’s frame were not shown.

Therefore, the contributions presented in this paper are twofold. The first is a set of intuitive teleoperation strategies that enable the inertia-based motion capture suit to control different frames of the quadrupedal legged manipulator. The second is the further development of our WBC previously developed in [19] to tailor it specifically for teleoperation applications through designing specific constraints to aid the teleoperator, namely halt and CoM constraints. This in turn enables the teleoperator to fully utilise robot redundancy for task completion, which was not possible in our previous framework [11].

This paper is organised as follows. Section 2 describes the hardware used for the robot platform and the teleoperation control device. Section 3 outlines the WBC framework, optimisation tasks and constraints. In Sect. 4, three teleoperation strategies using the motion capture suit are described. Section 5 details the simulation tests performed using the WBC framework with the proposed teleoperation strategies, while Sect. 6 covers these tests again but carried out using real-life hardware. In Sect. 7, the research is summarised and discussed.

2 System Description

This system consists of the Laikago quadrupedal robot, the ViperX 300 robotic arm and, for teleoperation, the Noitom Perception Neuron motion capture suit. Laikago is a lightweight quadrupedal robot capable of holding a payload of 5 kg. Mounted on the top of the Laikago is the 5 DoF ViperX 300 robotic arm. The arm had previously been redesigned with carbon fibre rods in place of the aluminium box section [11], to alleviate additional mass from the Laikago. Controlling this system is the inertia-based wearable motion capture suit, consisting of 16 IMU devices on each link of the human body. The suit collects skeleton data, allowing for control algorithms to make use of human body motion. This system has also been used over a more basic controller, such as a gamepad with joysticks, as they are better suited for end-effector control tasks, as demonstrated in [14]. Connecting these devices together involves the use of a Windows computer for the motion capture suit, a Ubuntu computer for the robot and a 5 GHz Wi-Fi router to communicate between them. The entire system is illustrated in Fig. 1.

3 Whole-Body Control Framework

3.1 Formulation of Optimisation Problem

To set up the WBC optimisation problem, a Quadratic Programming (QP) problem is formulated using the IK cost function to optimise for joint velocities \(\boldsymbol{\dot{\theta }}\), while subject to a range of constraints. The QP problem takes the form of

$$\begin{aligned} \min _{\boldsymbol{\dot{\theta }}} \quad&\frac{1}{2}\boldsymbol{\dot{\theta }}^T {\boldsymbol{A}}^T {\boldsymbol{A}}\boldsymbol{\dot{\theta }}-{\boldsymbol{b}}^T {\boldsymbol{A}}\boldsymbol{\dot{\theta }} \end{aligned}$$
(1)
$$\begin{aligned} \text {s.t. } \quad&{\boldsymbol{C}}_\text {lb} \le {\boldsymbol{J}}_{CoM}\boldsymbol{\dot{\theta }} \le {\boldsymbol{C}}_\text {ub}\, , \end{aligned}$$
(2)
$$\begin{aligned}&{\boldsymbol{J}}_{\text {halt}}\boldsymbol{\dot{\theta }}=0\, , \end{aligned}$$
(3)
$$\begin{aligned}&\boldsymbol{\dot{\theta }}_{\text {lb}} \ge \boldsymbol{\dot{\theta }} \ge \boldsymbol{\dot{\theta }}_{\text {ub}}\, , \end{aligned}$$
(4)
$$\begin{aligned}&\boldsymbol{\theta }_{\text {lb}} \ge \boldsymbol{\theta } \ge \boldsymbol{\theta }_{\text {ub}} \, , \end{aligned}$$
(5)

in which the problem is subject to CoM (2), halt (3), joint velocity (4) and joint position (5) constraints, who’s specifics are covered in later sections.

To implement the Cartesian and joint tasks of the WBC, \({\boldsymbol{A}}\) and \({\boldsymbol{b}}\) of (1) are formed as

$$\begin{aligned} {\boldsymbol{A}}={\begin{bmatrix}\alpha _{\text {Cart}}{\boldsymbol{A}}_{\text {Cart}} \\ \alpha _{\text {Jnt}}{\boldsymbol{A}}_{\text {Jnt}} \end{bmatrix}} \in {\mathbb {R}}^{\text {(6m+n)}\times \,\textrm{d}}, {\boldsymbol{b}}={\begin{bmatrix}\alpha _{\text {Cart}}{\boldsymbol{b}}_{\text {Cart}} \\ \alpha _{\text {Jnt}}{\boldsymbol{b}}_{\text {Jnt}}\end{bmatrix}} \in {\mathbb {R}}^{\text {6m+n}} \, , \end{aligned}$$
(6)

so that the QP problem can solve for tasks simultaneously. \(n=12+5\) is the number of joints of the legged manipulator, \(d=23\) is the number of DoF of the legged manipulator, \(m=5+1\) is the number of Cartesian tasks, and \(\alpha _{\text {Cart}}\) and \(\alpha _{\text {Jnt}}\) are the tasks weights used to prioritise critical tasks over others based on the application. This task weighting method has been used as opposed to a hierarchical method as it has a lower computational cost due to only one QP problem being solved per time step compared to solving several sequential problems, resulting in a computational time for each QP solve being within 1 ms. The details of the tasks stacked in (6) are outlined in the following sections.

Fig. 2.
figure 2

Block diagram of the WBC framework, built around the QP problem.

Cartesian Tasks. Cartesian tasks are used to reduce the residual between a reference Cartesian trajectory and the current Cartesian configuration of a frame of the robot. To achieve a high level of utility, this task will be applied to all end-effector frames and the trunk frame, in accordance with Fig. 2, making a wide variety of movements and tasks to be feasible. This task is realised by applying the Jacobian matrix of the frame, which maps Cartesian velocity to joint velocities, causing it to experience a velocity that moves it through the trajectory. This task is implemented within \({\boldsymbol{A}}\) and \({\boldsymbol{b}}\) as

$$\begin{aligned} {\boldsymbol{A}}_\text {Cart}={\boldsymbol{WJ}} \in {\mathbb {R}}^{\text {6m}\,\times \,\textrm{d}}, \quad {\boldsymbol{b}}_\text {Cart}={\begin{bmatrix}\boldsymbol{\dot{r}}_1^T\cdots \boldsymbol{\dot{r}}_m^T\end{bmatrix}} \in {\mathbb {R}}^{\text {6m}}, \end{aligned}$$
(7)

where \({\boldsymbol{J}}={\begin{bmatrix}{\boldsymbol{J}}_{1}^T\cdots {\boldsymbol{J}}_{m}^T\end{bmatrix}} ^T\), \({\boldsymbol{J}}_{i} \in {\mathbb {R}}^{\text {6}\,\times \,\textrm{n}}\) is the combined Jacobian matrix of all controlled frames, \({\boldsymbol{W}} \in {\mathbb {R}}^{\text {6m}\,\times \,\textrm{6m}}\) is a diagonal weight matrix used to scale the degree to which the frame is allowed to deviate from the reference trajectory; a higher weight increases strictness. The target Cartesian task frame velocity

$$\begin{aligned} \quad \boldsymbol{\dot{r}}_{i}=\boldsymbol{\dot{r}}_{i}^\text {target}+{\boldsymbol{K}}_\text {Cart}({\boldsymbol{r}}_{i}^\text {target}-{\boldsymbol{r}}_{i}^{\text {fk}}) \end{aligned}$$
(8)

describes the required target velocity for a frame to execute a reference trajectory using the velocity control law presented in [10], where \({\boldsymbol{r}}_{i}^{\text {fk}} \in {\mathbb {R}}^{\text {6}}\) is the current frame configuration calculated through forward kinematics, \({\boldsymbol{r}}_{i}^\text {target}\in {\mathbb {R}}^{\text {6}}\) is the target frame configuration, \(\boldsymbol{\dot{r}}_{i}^\text {target}\in {\mathbb {R}}^{\text {6}}\) is the target frame velocity, and \({\boldsymbol{K}}_\text {Cart}\) is the task gain. It should be noted that all configuration orientations are described in Euler angles.

Joint Tasks. To enforce specific characteristics on each joint of the robot, joint tasks are added to the QP problem. In this framework, the joint damping task is added for all joints of the robot to reduce high-frequency oscillations, caused by the overshoot of the Cartesian tasks, to improve stability. Aligning with (6), these joint tasks take the following form,

$$\begin{aligned} {\boldsymbol{A}}_\text {Jnt} = {\boldsymbol{S}}, \quad {\boldsymbol{b}}_\text {Jnt} = \dot{\boldsymbol{\theta }}_{\text {i prev}}^*, \end{aligned}$$
(9)

\({\boldsymbol{S}}\in {\mathbb {R}}^{\text {n}\,\times \,\textrm{n}}\) and \(\dot{\boldsymbol{\theta }}_{\text {i prev}}^* \in {\mathbb {R}}^{\text {n}}\) are the damping joint task weight, selection matrix, and optimised joint velocities for the last time step respectively. Further joint tasks could be used within (9), see [19] for details of these tasks.

Constraints. Constraints are used within the QP problem to refine the solution space. To improve the stability of the robot, the CoM stability constraint (2) utilises the CoM Jacobian \({\boldsymbol{J}}_\text {CoM}\) to force the CoM to lie within the support polygon, based on the position of the feet in contact with the ground. Within (2), the lower and upper bounds of the inequality constraint are

$$\begin{aligned}&{\boldsymbol{C}}_\text {lb} = \frac{({\boldsymbol{r}}_{\text {lb}}-{\boldsymbol{r}}_{\text {CoM}}^{\text {fk}})}{\delta t} \,, \quad {\boldsymbol{C}}_\text {ub} = \frac{({\boldsymbol{r}}_{\text {ub}}-{\boldsymbol{r}}_{\text {CoM}}^{\text {fk}})}{\delta t} \,, \end{aligned}$$
(10)

where \({\boldsymbol{r}}_{\text {lb}}\) and \({\boldsymbol{r}}_{\text {ub}}\) are the lower and upper bounds of the support polygon respectively, \({\boldsymbol{r}}_\text {CoM}^{\text {fk}}\) is the current position of the CoM, \({\boldsymbol{J}}_\text {CoM}\) is the CoM Jacobian, and \(\delta t\) is the time step.

The halt equality constraint (3) has also been applied to the QP problem, in which \({\boldsymbol{J}}_{\text {halt}}={\begin{bmatrix}{\boldsymbol{J}}_{1}^T\cdots {\boldsymbol{J}}_{c}^T\end{bmatrix}} ^T\), where \({\boldsymbol{J}}_{i} \in {\mathbb {R}}^{\text {6}\,\times \,\textrm{n}}\) is the Jacobian of the frame to be constrained, and c is the number of these constraints. Adding this constraint to a frame ensures it has zero velocity. Hence, this constraint proves critical when a non-slip condition is required at the feet of the robot, or when the gripper is to remain static in either its position, orientation or both during manipulation tasks.

The final constraints, (4) and (5), ensure that the solutions of the QP problem respect the joint limits of the robot, where \(\boldsymbol{\dot{\theta }}_{\text {lb}}\) and \(\boldsymbol{\dot{\theta }}_{\text {ub}}\) are the joint upper and lower velocity limits, and \(\boldsymbol{\theta }_{\text {lb}}\) and \(\boldsymbol{\theta }_{\text {ub}}\) are the upper and lower joint position limits.

4 Teleoperation Strategies

The human body and the quadrupedal robot and manipulator are kinematically dissimilar, therefore direct mapping of the teleoperator’s body to the robot is not viable. Thus, three teleoperation strategies (TS) are developed to intuitively teleoperate the legged manipulator via WBC, which use both hands of the motion capture suit to select the TS and the right hand to generate a reference trajectory. The proposed three strategies are as follows with the specific had poses detailed in Fig. 3,

  • TS0: no reference is sent to the robot, acting as a safety feature.

  • TS1: the relative teleoperator’s arm movement is sent to control the pose of the gripper.

  • TS2: the relative teleoperator’s arm movement is sent to control the pose of the trunk.

  • TS3: the gripper is locked in both position and orientation, and the relative teleoperator’s arm movement is sent to control the pose of the trunk.

Fig. 3.
figure 3

The corresponding hand poses to activate each TS.

When one strategy is activated, the current pose of the right hand in the world frame is extracted from the motion capture suit and taken as the origin of the trajectory reference, with any subsequent movements being compiled and passed to the WBC framework. A relative scaled pose relationship is developed to map motions between the teleoperator and the robot, where at time t, the pose of the robot’s frame of interest is modelled as

$$\begin{aligned} {\boldsymbol{h}}_{sd}^{t}={\boldsymbol{h}}_{sd}^{0}+\boldsymbol{\mu }({\boldsymbol{h}}_{m}^{t} - {\boldsymbol{h}}_{m}^{0}) \end{aligned}$$
(11)

where \({\boldsymbol{h}}=[x; z; y; r; p; y]\) represents the displacements in the sagittal (x), lateral (y) and vertical (z) directions and the rotations in the roll (r), pitch (p) and yaw (y) directions. Subscript m refers to the master, s to the slave, d to a desired value and 0 refers to the initial timing when the hand is closed. \(\boldsymbol{\mu }\) is the scaling factor for motions between the master and the robot. Orientation is not scaled by the scaling factor, therefore \(\mu _{\text {r}},\mu _{\text {p}},\mu _{\text {y}}=1\).

5 Simulations

To validate the effectiveness of the teleoperation system paired with the WBC framework, a physics-based PyBullet simulation was completed using the Laikago quadruped and ViperX 300 arm robots. During the simulation, three case studies were completed to test all three teleoperation strategies. During each study, a reference is generated by the teleoperation algorithm from the inertia-based motion capture suit, running at 500 Hz, and sent to the WBC framework, also running at 500 Hz.

Fig. 4.
figure 4

The WBC framework output of (a) orientations and (b) positions for the gripper and trunk frames covering all five tests.

For teleoperation strategies TS1, TS2, and TS3, tests were completed to validate the WBC framework’s ability to track the input reference. Between each case study, the posture of the teleoperator’s hand is used to switch between teleoperation strategies, as outlined in Sect. 4. It should be noted that all other references that were not being controlled through teleoperation were kept constant from their initial positions. For all studies that do not require the feet frames to move, halt constraints were added for these frames, as outlined in (3), keeping them locked in position. For the following case studies and the data presented in Fig. 4, the trunk frame is aligned with the world frame at the beginning of the first test, TS1.1. The world frame was set so that the \(+x\) axis was in the direction the robot is facing, \(+y\) was to the left of the robot, and \(+z\) was in the upwards vertical direction. Furthermore, within Fig. 4 the Cartesian positions and orientations are estimated through completing forward kinematics using the joint positions output by the WBC.

Across the case studies, three different types of movement from the teleoperator were used. This is a sweeping movement to the right (M1), a central vertical movement (M2), and a central thrusting movement forward (M3), with each movement type being completed twice sequentially. This was to explicitly demonstrate the capabilities of the WBC framework. For each test within these studies, references were input into the Cartesian task for either the gripper or trunk frame, with negligible latency being observed between these input references and robot motion generated by the WBC. For the frame that is being controlled, its task weight was set relatively high within the QP problem so that optimisation prioritised this task. A video of all proceeding simulations and testing is available onlineFootnote 1.

Fig. 5.
figure 5

Snapshots of the gripper frame rotating in the yaw axis during TS1.1.

5.1 TS1 Case Study

For the case study of TS1, all three different types of movement from the teleoperator were used. This being M1, M2, and M3 to supply references for tests TS1.1, TS1.2, and TS1.3 respectively. Distinct WBC characteristics were observed in all three tests, where the robot adjusted to aid in the gripper frame to meet its target trajectory. These characteristics are portrayed in Fig. 4, where the position and orientation of the gripper and trunk frame, for all studies, are presented. Within these graphs, for TS1.2 the trunk’s z position and pitch angle can be seen to increase, and for TS1.3, the trunk’s z position, x position, and pitch angle increase. This demonstrates how the WBC utilises the trunk frame to realise the gripper frame’s Cartesian task. Furthermore, in TS1.1, WBC characteristics can be seen as whilst the gripper frame follows a yaw angle reference trajectory, the trunk can be seen to utilise many of its redundant DoF (x, y, roll, pitch, and yaw) to aid in realising the gripper’s trajectory. This is further demonstrated in Fig. 4 and 5.

The effectiveness of the WBC framework is further emphasised in TS1.3, as shown in Fig. 6, where in the top row the WBC is disabled, and in the bottom row it is enabled. Without the WBC, the manipulator was observed to be unable to reach the desired position and a singularity was reached. Whilst with WBC enabled, the desired position was met and no singularities were observed. Therefore, this demonstrates how the WBC framework is able to take a teleoperation input reference and utilise all DoF of the robot to realise it.

Fig. 6.
figure 6

Snapshots comparing the gripper frame moving through the x-axis driven by data from the motion capture suit during TS1.3 with the WBC disabled (top row), and enabled (bottom row).

5.2 TS2 Case Study

Test TS2.1 utilised the teleoperation strategy TS2. During this case study, the gripper frame was locked in place in terms of position using (3). The frame being controlled by the teleoperator switched to the trunk frame. For this test, M1 was used to send a y reference to the trunk Cartesian task within the WBC framework. As presented in Fig. 7, this resulted in the translation of the trunk frame in the y direction while the gripper frame remained in a constant position, but its orientation moved freely. This is supported by Fig. 4, where the position of the gripper frame remains constant throughout the test, whilst its orientation rotates in the roll and yaw axis. Simultaneously, the trunk frame can be seen to translate in the y direction. This demonstrates the effectiveness of the WBC framework in keeping the gripper frame locked in position whilst the trunk exploits the system’s redundancy to change its posture. Applying this constraint to only positions can aid in the robot realising tasks for other frames. This is because it increases the solution space of the QP, as a wider range of robot configurations are valid while satisfying the constraint. During this test, the CoM moves significantly due to the movement of the trunk which could potentially affect the robot’s stability. However, it is evident from Fig. 8 that in not only this test but across all tests the centre of pressure (CoP) remains within the stability limits defined by the position of the feet. In turn, this suggests that the CoM constraint, defined in (2) aids in preserving stability.

Fig. 7.
figure 7

Snapshots of the trunk frame translating in the y direction with the gripper constrained in position during TS2.1.

Fig. 8.
figure 8

Centre of pressure across all five tests.

5.3 TS3 Case Study

During this case study, the TS3 teleoperation strategy was implemented to lock the gripper frame in both position and orientation, while the trunk frame was controlled using the teleoperation reference. Consequently, the trunk Cartesian task has a relatively high weight. For test TS3.1, M2 was used to send a z reference to the trunk Cartesian task. For this test, the gripper frame was observed to stay locked in position and orientation using (3), while the trunk frame completed its trajectory in z. These observations are presented in Fig. 4 and Fig. 9, where the position and orientation of the gripper frame can be seen to be constant while the trunk frame translates through the z direction.

Although all other components of the input reference for the trunk frame’s Cartesian task were constant, translation in x was observed, as detailed in Fig. 4. This observation was caused by the reduced solution space that fully constrains the gripper frame, in both position and orientation, results in. Therefore, due to this reduced solution space, the QP problem within the WBC framework had to sacrifice the strictness at which the trunk Cartesian task is tracked.

Fig. 9.
figure 9

Snapshots of the trunk translating in the z direction with the gripper constrained in position and orientation in TS3.1.

6 Hardware Experiments

The same series of studies presented in Sect. 5 were tested using real-life hardware, to analyse the overall framework’s effectiveness in realising input teleoperation references. Regarding hardware, the A1, ViperX 300 arm, and Noitom Perception Neuron motion capture suit are set up as detailed in Sect. 2, with exception of using an A1 quadruped instead of a Laikago to demonstrate the proposed framework’s generality, and the addition of the Ubuntu computer being connected to the A1 via Ethernet connection and the ViperX 300 arm via USB.

From completing this series of studies, it has been observed that the performance of the robot exhibits all whole-body motion characteristics as presented in Sect. 5, which can be shown in Fig. 10. Furthermore, very little latency is observed between the A1 and ViperX 300, resulting in effective cooperative motion between the two robot systems. Consequently, not only does this demonstrate this framework’s ability to be deployed onto hardware successfully, but also its modularity by successfully completing tests using the A1 and Laikago quadrupeds. This has served as preliminary testing, further analysis and more complex tests will be carried out in future work.

Fig. 10.
figure 10

Snapshots of the A1 ViperX 300 robot completing the tests of the different case studies.

7 Conclusion

In this paper, a highly functional teleoperation system that integrates a wearable inertia-based motion capture suit, three intuitive teleoperation strategies and a WBC framework to control quadrupedal legged manipulators has been proposed. By implementing a range of modular tasks and constraints within a QP optimisation problem, the teleoperation system can take input references and utilise WBC control to realise them through applying a teleoperation strategy, based on the application. The proficiency of the WBC framework to utilise the different teleoperation strategies was demonstrated, through simulation and preliminary hardware testing, in which it was used to complete a range of frame control tasks.

Future work will include expanding the teleoperation strategy functionality and full experimental validation of this teleoperation system on the real robot. Other future work could involve broadening the teleoperation strategies to use other elements of the inertia-based motion capture suit, implementing a method of dynamically weighting tasks, and integrating a wider range of gaits the teleoperator could use. To aid in the aforementioned further development of the teleoperation strategies, an index of performance will be created to analyse their effectiveness.