1 Introduction

Object handover is a fundamental skill to endow robots with the ability to collaborate with humans in everyday tasks. Human–robot object handover involves many complex aspects such as human and object safety, social and handling context, grasping stability, slip detection, and ergonomics. Huge research efforts have been devoted to endow robots with the skills required for sharing objects, working and collaborating with humans. However, there is still a need for safe, smooth, and reliable interaction in any combined task.

Humans show a high degree of adaptability when exchanging objects with a robot (Edsinger and Kemp 2007). Notwithstanding, to ensure the safety of the robot hand and the object, robot–human object handover typically aims to facilitate the task for the human (Huber et al. 2008). To endow robots with ability to safely interact in complex situations, such as a workshop or an operating room, the system should ensure smooth and reliable handovers even if the human cannot securely grasp the object from the robot. Performing reliable object handover requires a system capable of adapting against uncertain events and perturbations that are not meant to end in a handover, such as a receivers unsecured grasping or collisions. In situations like these, the robot should be able to keep itself and the object safe. Avoiding both damage to the hand and the object falling is an extremely complex problem which requires quick readjustment of the fingers to maintain a stable grasp during a potentially large perturbation. One promising approach to solve these problems and facilitate manipulation is through tactile sensing (Liu et al. 2015; Kappassov et al. 2015; Yousef et al. 2011). However, state-of-the-art approaches assume that there are no perturbation forces applied on the object during the handover. This paper contributes to reliable object handover by presenting a tactile sensing based handover algorithm that ensures neither the robot nor the object are damaged. We achieve this by adapting to force perturbations on the object and releasing only if the human is ready to hold the object. The proposed approach was evaluated on a tendon-driven Shadow robotic hand equipped with BioTAC tactile sensors as shown in Fig. 1, and represents a step towards endowing robots with reliable systems that allow them to collaborate with humans in scenarios where fragile objects have to be handed over, for instance by robotic assistants in offices, homes, and hospitals, and caregiver robots for the elderly.

Fig. 1
figure 1

Robot handing over an object to a human

A fundamental problem in safe robot–human handover is deciding when to release the grasp and, thus, allow the object transfer. Since a robotic hand has to maintain a stable grasp on the object until the human is ready to hold it, the approach in Nagata et al. (1998) considered a tight relationship between object handover and grasp stability to trigger the object release. A three fingered robotic hand released an object when the forces applied on the object change a number of grasp stability metrics. In particular, the authors used a combination of joint angles, contact, kinematic, and dynamic stability indices of the hand to decide whether to release the object (robot–human handover), to hold it (human–robot handover), or to re-grasp it using a new finger configuration. The approach presented in Aleotti et al. (2014) used a Kinect sensor to detect the receiver hand and the object, and released the object when both where detected as a single cluster of 3D points. Although the authors implemented a complete handover procedure, the system was not reliable since the object could be released even when the receiver was not grasping it. The work presented in Bohren et al. (2011) proposed a mechanism to handover a drink, where the robot opened the gripper only if a human face was detected and simultaneously the compliant hand of a PR2 was displaced by one centimetre in the vertical direction. Despite handing over the object in a secure manner, their approach requires the human receiver to pull the object strong enough to move the arm above some threshold, which impacts on the system responsiveness. The first effort to imitate the actual way humans handover objects is presented in Kim and Inooka (1992). Their experiments showed that humans adapt the grasping force according to the change in the estimated weight of the object. The authors used a two finger hand and force sensors to release the object according to its slippage, i.e. the tipping point on the Coulomb force.

A thorough analysis of human handover was presented in Chan et al. (2012) and their results were subsequently used in Chan et al. (2013) to implement a release controller on a PR2 robot. Their human-inspired handover system controlled the grip force of the robot according to the weight of the object the robot perceived in the wrist. Moreover, the authors found a user preference for the human-inspired controller when compared with four other handover controllers for quick release and constant grip forces. Another approach relying on the sensed load force was presented in Medina-Hernández et al. (2016), which implements a grip force controller based on the feedback of a force/torque sensor installed on a KUKA LWR robot with an Allegro hand attached. The authors found that the object handling occurs faster when using their controller compared to state-of-the art approaches. Furthermore, their approach significantly reduces the forces applied on the object by the robot and the human, resulting in fast and smooth handovers.

Although most of these works rely on some force estimate acting upon the object, they all assume the handover is going to take place without problem. In a recent work (Parastegari et al. 2016) a system consisting of acceleration and force sensors mounted on a gripper was used to ensure fail-safe handovers. The authors compared the grip force with the sum of forces applied to the object for a given static friction coefficient, and implemented a controller for re-grasping if the object’s downward acceleration exceeds a given threshold. Another solution to the grasp release problem was presented in Gómez-Eguíluz et al. (2017a) through a novel reliable object handover algorithm implemented on a Shadow Robot Hand equipped with BioTAC tactile sensors. The robot released the object only if the force applied to the object was perceived to have a direction perpendicular to the palm, and ensured the safety of the robot by adapting the grasping to account for the external forces and torques. In Konstantinova et al. (2017), a bidirectional handover approach (i.e human-to-robot and robot-to-human) was implemented in a mobile robot equipped with a 5 degrees of freedom arm and a soft robotic hand. Their system relies on force/torque information measured at the wrist and releases the object in a timely manner, while the underactuated soft robotic hand provides mechanical adaptation to physical interactions with the environment. These works, Parastegari et al. (2016), Gómez-Eguíluz et al. (2017a) and Konstantinova et al. (2017) recognise that in some situations the robot should not release the object, especially if the force applied on it does not have the right direction. However, they are rather limited in the detection of set of directions in which the receiver will pull from the object. The work in Gómez-Eguíluz et al. (2017b) evaluated the approach for a reliable controller presented in Gómez-Eguíluz et al. (2017a) with a group of naïve participants. Although all human users pulled from the object when receiving it from the robot, the pulling direction changed depending on the experimental conditions. To deal with this issue, the authors presented a classification approach to detect the pulling force direction. However, the classification accuracy shown in Gómez-Eguíluz et al. (2017b) was not high enough to ensure the safety of the object.

In order to endow robots with reliable handover capabilities, the system should ensure the safety of both the object and the robot, which entails minimizing the number of false positives in the detection of the force direction. This paper presents a novel algorithm for robot–human reliable handovers that extends our previous work (Gómez-Eguíluz et al. 2017a, b). The contribution of this paper is twofold. First, we present a new event detection system that perceives perturbations being applied on the object in any direction. Finally, we extend the algorithm in Gómez-Eguíluz et al. (2017b) to enhance its reliability, and evaluate the system to maximise safety. The rest of the paper is organised as follows. Section 2 presents the effort controller and force estimation procedures, followed by the perturbation force direction detection approach and the reliable object handovers algorithm. Section 3 shows results on perturbation trajectory filtering, object perturbation release detection, force adaptation and object handover. Section 4 ends the paper presenting conclusions and some directions for future work.

2 Reliable object handover controller

The approach proposed uses a control system to keep the object grasped, adapting the hand configuration as necessary. It decides when to release based on two events: the change in the perceived load force and the perturbation force direction.

2.1 Grasping effort controller

The proposed approach assumes that the object being handed over is rigid, the initial configuration of the hand is ready for the handover, and a stable precision grasp using three fingers is set. Using a fixed position control, a force perturbation would result in a contact loss or increased efforts in the joints, which could result in broken tendons on the experimental platform. To illustrate the effect of forces when controlling the position of the fingers we performed an experiment where a perturbation force was applied to a single finger of our Shadow robotic hand equipped with BioTAC tactile sensors. Figure 2 shows a comparison of the response in the norm of the force of the middle finger over time for the proposed effort controller and a position control (see Sect. 2.2 for how to compute the force). Although the Shadow hand fingers provide some compliance through their mechanical design with tendons and springs, the force sensed for a small perturbation using a position control is more than twice the force sensed when the effort controller is running, which significantly reduces the risk of damaging the hand.

Fig. 2
figure 2

Changes in the fingertip force length for effort versus position control

We index the fingers used for grasp the object as \(j=1,2,3\), where \(j=1\) is the thumb, \(j=2\) is the first finger, and \(j=3\) is the middle finger. The effort controller adapts the hand configuration to maintain an initial wrench, i.e. force and torque, while adapting to perturbation forces on the object. We can obtain the wrench \(^{B}{{\bar{\mathbf{F }}}}_j\) we set on the hand for the stable grasping in the robot base reference as:

$$\begin{aligned} ^{B}{{\bar{\mathbf{F }}}}_{j}=J_j({\mathbf {q}}_j)^\dagger \varvec{\Gamma }_j, \end{aligned}$$
(1)

where \({\mathbf {q}}_j\) are the configuration of the finger joint, \(\varvec{\Gamma }_j\) their corresponding torques or efforts, \(J_j({\mathbf {q}}_j)^\dagger \) is the pseudo-inverse of the Jacobian for finger j, and the superscript B states the wrench is in the base reference frame. The necessary conditions to maintain a stable grasp can be obtained by converting the forces and torques of the initial wrench to the object reference frame and taking into account the friction coefficients, and the normals at the contact points.

In order to maintain the stability of the grasp in the presence of a perturbation the robot could use a position control for its fingers, but that implies commanding large torques to the joints, which may damage the hand. An alternative to ensure the hand is not damaged would be to keep the wrenches in the object reference frame \(^{O}{{\bar{\mathbf{F }}}}_j\) constant, but that would work as long as the palm pose suffers only small changes, i.e. for small perturbations. Maintaining the wrenches in the object reference frame has two important drawbacks; first, the perturbation force can be used to “control” or “drive” the hand; and, second, the stability of the grasp could be lost (leading to the object being dropped). Instead of controlling the hand position or maintaining the wrenches in the object reference frame, we opt for keeping and restoring the contact forces and torques as computed in the base frame \({}^B{{\bar{\mathbf{F }}}}_i\) for a stable grasp for each finger. Using the proposed approach allows the robot to adapt smoothly to perturbations while keeping the object grasped close to the stable configuration, thus, preventing the hand to be damaged and the object to fall. The effort joint control considers the fingers individually and uses the given stable grasp wrench \({}^{B}{{\bar{\mathbf{F }}}}_i\) as a reference while the perturbed measured wrench \({}^B\mathbf F _j\) is fed back to the controller. Therefore, given the difference between the jth finger contact wrench \({}^B\mathbf F _j\) and the one for the stable grasp we apply to the finger’s joints the efforts:

$$\begin{aligned} \varvec{{\Gamma }}_j= K_jJ_j({\mathbf {q}}_j)^T\left( {}^{B}{{\bar{\mathbf{F }}}}_j-{}^{B}\mathbf F _j\right) , \end{aligned}$$
(2)

where \(J_j({\mathbf {q}}_j)\) is the Jacobian of finger j at the joint position \({\mathbf {q}}_j\), and \(K_j\) is a square gain matrix of size equal to the joints to control. Thus, for instance, the finger moves backwards to keep the force constant if a perturbation increases the contact force while maintaining the direction and torque. Generally, the product of a perturbed wrench and the Jacobian results in motion of the finger to compensate for external forces and torques. When a perturbation force is applied (since the grasped object is rigid), a change in the contact force and torques is perceived by all three fingers. All fingers move individually to maintain the stable grasping wrench in the base frame. As the friction of the rubber fingertips of the BioTAC is large, the motion can have a different effect on the wrenches in the object reference frame. However, we experimentally found that this control mechanism kept a stable grasp while the object moved due to external perturbations. In this manner the proposed control mechanism implements compliance in the tactile force.

Fig. 3
figure 3

Scene coordinate frames diagram

Figure 3 represents the different coordinate frames of the hand used in the rest of the paper; the base frame of the forearm B, the object frame O, and the end-effector frames \(E_j\) corresponding to each fingertip or BioTAC sensor. The transformations between B and E (\(^BT_E = ^BT_{E_j}\) omitting the index for the finger) can be easily computed using the forward-kinematics of the manipulator, while the wrenches/forces applied to the object are computed in the reference frame of each individual BioTAC.

2.2 Cartesian force estimation using the BioTAC

When the hand joints have torque sensors attached, the wrench applied to the object can be easily computed from the measured torques \(\varvec{\Gamma }\) using the pseudo-inverse Jacobian matrix for the corresponding configuration \(J({\mathbf {q}})^\dagger \) as \(^B\mathbf F =J(\theta )^\dagger \varvec{\Gamma }\). However, the sensors included in the joints of the Shadow hand measure the differential effort (i.e. differential tensions) on the tendons (Elias), not the applied torque in the joints. Therefore, we present an alternative approach—using SynTouch BioTAC (Fishel et al. 2013) tactile sensors—to estimate the contact forces in the fingertips \(^B\mathbf f \) instead of the applied wrench.

The BioTAC is a biomimetic tactile sensor that provides a number of sensing modalities such as micro-vibration, pressure, temperature, heat flux and fingertip compliance. Although the BioTAC is not a force sensor we can estimate the contact force from its measurements. Specifically, we can compute the contact force by using the pressure, the contact area, and the normal vector to the object surface. While the pressure measurements are obtained from the BioTAC’s raw data, the contact area and the normal vector to the object surface are estimated from the skin deformation. Upon contact, the increase in the pressure measured by the BioTAC (P) can be converted into the norm of a contact force (\(|\mathbf f |\)) by simply using the relation \(|\mathbf f |=Pa\), where a is the contact area with the object. Although the pressure is obtained from the sensor, the contact area can only be estimated from impedance measurements from 19 electrodes located across the finger core. The measured impedance is directly related to the distance between the core and the rubber skin at their corresponding locations and the impedance value with respect to the resting level, i.e. no contact, decreases when the rubber skin is deformed.

We use the BioTAC sensor and the approach presented in Gómez-Eguíluz et al. (2016) to approximate the contact area corresponding to each electrode i as a circle of radius \(r_i\) equal to half the distance between the electrode and its nearest neighbour. The total contact area of the fingertip can be obtained as a weighted average of these individual areas:

$$\begin{aligned} a= & {} \sum _{i}\lambda _i\pi r^2_i, \end{aligned}$$
(3)

where \(\lambda _i\in [0,1]\) is an impedance dependent scale factor. To estimate the scale factor \(\lambda _i\) we define a piece-wise linear function of the change of the impedance value \(e_i\) of each electrode relative to the resting level \({\bar{e}}_i\) as:

$$\begin{aligned} \lambda _i= & {} {\left\{ \begin{array}{ll} 1&{}\quad {\text {if }}\;e_i\le e_m\\ 1 - \frac{e_i-e_m}{{\bar{e}}_i-e_m} &{}\quad {\text {if }}\;e_m< e_i < {\bar{e}}_i\\ 0&{}\quad {\text {if }}\;e_i\ge {\bar{e}}_i \end{array}\right. } \end{aligned}$$
(4)

where \(e_m\) is a lower impedance threshold to saturate the calculation of the contact area around the electrode (in our case experimentally fixed to \(e_m=-\,400\)). Thus, \(\lambda _i\) is zero at the resting level (or above) meaning no contact at the electrode position, it linearly increases to 1 for decreasing impedances up to the threshold \(e_m\) , and is 1—maximum contact area—for values below the threshold.

Although the fingertip of the BioTAC also applies a torque at the contact point, there is no way to estimate it, nor to compute the component of the force tangential to the object. Therefore, we assume that the full length of the force is applied in the direction perpendicular to the contact surface. We use the technique presented in Su et al. (2012) to estimate the contact direction based on the unit vectors normal to the BioTAC fingertip at each electrode position. Similar to the approach used to compute the area, a weighted average of the normal vectors using the change in the corresponding impedances relative to the resting levels is used to compute the contact direction. Given the normal vectors for the BioTAC electrodes—constant in the fingertip reference frame \(E-{{\hat{\mathbf {n}}}}_i,\quad i=1,\ldots ,19\), the total estimate of the contact force can be computed as:

$$\begin{aligned} ^E\mathbf f =\frac{|\mathbf f |}{|\sum _i\lambda _i{{\hat{\mathbf {n}}}}_i|} \sum _{i}\lambda _i{{\hat{\mathbf {n}}}}_i, \end{aligned}$$
(5)

where \(\lambda _i\) and the force norm |f| are defined above. It is worth noting that Eq. 5 corresponds to the contact force in the reference frame of the fingertip. For simplicity, and unless stated otherwise, we denote by E the reference frame of the end-effector of any finger j, i.e. \(E = E_j\), since all fingers are processed identically. As we will see in Sect. 2.4, the proposed object handover algorithm uses \(^E\mathbf f \) to detect the perturbation force direction and to trigger the object release. Additionally, we need to convert the estimated forces to the base frame \(^B\mathbf f \) as they are used in the proposed grasping effort controller and they are the basis to detect the variations on the load force.

2.3 Load force variations for event detection

The proposed handover algorithm was designed to release the object based on two events: the detection of a perturbation event and the right pulling force direction. We use the change in the perceived load force to identify when a perturbation has been applied on the object and, thus, trigger a classification process (see Sect. 2.5) to identify the direction of the object pulling force. Therefore, at every time step, we update a fixed size sliding window of duration \(\Delta t\) seconds (\(\Delta t = 0.05\)) to include the latest forces \({}^B\mathbf f \) measured by the BioTAC sensors. The window \({}^B{\mathcal {W}}\) is divided in two equal sized sequences \({}^B{\mathcal {W}}^1\) and \({}^B{\mathcal {W}}^2\), where \({}^B{\mathcal {W}}^1\) denotes the oldest data and \({}^B{\mathcal {W}}^2\) the most recent. We compute the averages over the windows and use them for detecting load force variations.

Most of the object handover approaches in the literature rely on changes in the load force to control grasping forces. Here, the estimate of the load force in the base frame \(^B\mathbf f _L\) corresponds to the sum of all the contact forces \({}^B\mathbf f _L = \sum \limits _{j}({}^B\mathbf f _j)\). In Gómez-Eguíluz et al. (2017a), we found that a change in the norm of \(^B\mathbf f _L\), \(\Delta {}^B\mathbf f _L\), can be detected when an external action is being carried out over the object. In the context of the reliable object handover algorithm, this norm change event triggers a classification process to identify the type of event as described below. When a perturbation force is applied on the object, the range in which the contact force varies is different for x, y and z coordinates with respect to the BioTAC’s frame. Because of the ranges of \(^B\mathbf f _L\), \(\Delta {}^B\mathbf f _L\) is more sensitive to perturbations in some directions than in others. For instance, despite being very sensitive for lateral perturbations with respect to the fingertips, the change in the norm was not as responsive for frontal movements due to contact force variations relying on a smaller range than for the lateral ones. In order to solve this issue, we take into account the scale of the contact force variations for each axis. Therefore, the variation on the load forces is computed as the Mahalanobis distance between \(\left<{}^B{\mathcal {W}}^1\right>\) and \(\left<{}^B{\mathcal {W}}^2\right>\):

$$\begin{aligned} \Delta {}^B\mathbf f _L = \left<{}^B{\mathcal {W}}^*\right>^T {}^B\varvec{\Sigma }^{-1} \left<{}^B{\mathcal {W}}^*\right>, \end{aligned}$$
(6)

where \(\left<{}^B{\mathcal {W}}^*\right> = \left<{}^B{\mathcal {W}}^1\right> - \left<{}^B{\mathcal {W}}^2\right>\), \(\left<{}^B{\mathcal {W}}^i\right>\) denotes the expected value of the corresponding sub-window \({}^B{\mathcal {W}}^i\), and \({}^B\varvec{\Sigma }^{-1}\) is the covariance matrix of \({}^B{\mathcal {W}}\). We empirically found values for \({}^B\varvec{\Sigma }^{-1}\) by computing the covariance of the load force \(^B\mathbf f _L\) using recorded data during a steady state of the hand, i.e. without perturbation forces applied. If \(\Delta {}^B\mathbf f _L\) exceeds a fixed threshold we can determine that an external force is acting on the object. The threshold \(f_{th}=0.002\) was experimentally chosen while slightly perturbing the object with the grasping effort controller running. It is worth noting that selecting \(f_{th}\) without using the grasping effort control system would generate a threshold value that is too large as the hand is not adapting to perturbations resulting in greater contact forces.

2.4 Features for force direction detection

Thus far, we can detect a perturbation force being applied on the object \({}^B\mathbf f _L\) exceeding a given threshold. However, as not all perturbations are expected to result in a handover, we also need to identify the direction of perturbation force that will trigger release if and only if it is safe to do so. To classify the direction of a perturbation force over the object, we modelled the variations of the contact force \(^E\mathbf f _j\) estimated using the BioTAC for each individual finger \(j=1,2,3\) with respect to their corresponding resting forces \(^E{{\bar{\mathbf{f }}}}_j\). Although the perturbation direction could be estimated in the reference frame of the forearm, i.e. using \({}^B\mathbf f _j\), we experimentally found that the consistency of the estimated direction was higher when computing features for the direction detection in the reference frame of the fingertips. The reason for this experimental result is that the perturbation direction in the base reference frame is affected by the uncertainty of the measurements of the joint angles. Moreover, selecting the fingertip frame to represent the perturbation direction allows to define constant directions relative to the configuration of the fingers, which are directly related to the grasped object. Given the initial grasp of the object, we compute the resting forces \(^E{{\bar{\mathbf{f }}}}_j\), as the average response within a window of \(\Delta t\) seconds. We use a sliding window, which is updated at the sensor sampling interval, to retain all \(^E\mathbf f _j\) estimates obtained during the last \(\Delta t\) seconds. As the human touches the object, potentially starting a handover, the robot computes the perturbed forces of each finger as the average of the forces in the sliding window \(^E\mathbf f _j = E\left[ ^E\mathbf f _j(t_k)\right] \). It is worth noting that both the resting and the perturbed forces are in the fingertip reference system.

We denote \(\theta _j^\mathbf{f }\) and \(\phi _j^\mathbf{f }\) the azimuth and elevation angles of the normalised contact perturbed force vectors for each finger j respectively, i.e. the spherical coordinates of the normalised force vector in the reference system of the fingertip. Similarly, \(\theta _j^{{{\bar{\mathbf{f }}}}}\) and \(\phi _j^{{{\bar{\mathbf{f }}}}}\) are, respectively, the azimuth and elevation angles of the normalised forces at the resting position. To identify the pulling force direction we define a feature vector containing the differences between the azimuth and elevation angles of the contact forces and those corresponding to the resting position forces of each finger in their corresponding fingertip reference frame, i.e. \(\theta _j = \theta _j^\mathbf{f }\, -\, \theta _j^{{{\bar{\mathbf{f }}}}}\) and \(\phi _j = \phi _j^\mathbf{f }\, -\, \phi _j^{{{\bar{\mathbf{f }}}}}\). The resultant feature vector \(\varvec{\vartheta }=(\theta _1, \phi _1, \theta _2, \phi _2, \theta _3, \phi _3)\) is the angular deviation of the contact forces, which is an invariant descriptor against changes on the hand position, object geometry and size.

Finally, a Kalman Filter was used to estimate the angular deviation velocities of the contact forces \(\dot{\varvec{\vartheta }}\). We will use the posterior state estimate \(\hat{\mathbf{X }}_{k|k}\) as the feature vector for detecting perturbation force directions (see Sect. 2.5). A constant velocity model was used to compute the state estimate \(\hat{\mathbf{X }}_{k+1}\) at time \(k+1\) from the true state \(\mathbf X _k\) at time k. The true state \(\mathbf X _k\) was obtained by concatenating the angular deviation of the contact forces \(\varvec{\vartheta }\) and their velocities \(\dot{\varvec{\vartheta }}\) at time k. We assume constant process and observation noise in the model and empirically found appropriate initialization for the covariance matrix of the process noise. Before detecting any event or pulling direction we collect readings during 5 s which were used to compute values of \(\varvec{\vartheta }\) and their covariance. We set the observation noise by using the covariance of \(\varvec{\vartheta }\) in the calibration data, which we assume was obtained without exerting any perturbation on the contact forces. Therefore, at each time step k we predict the state \(\hat{\mathbf{X }}_{k|k-1}\) and covariance matrix \(\mathbf P _{k|k-1}\) using the latest posterior estimate \(\hat{\mathbf{X }}_{k-1|k-1}\). Then, we update the posterior estimate for both the state \(\hat{\mathbf{X }}_{k|k}\) and covariance \(\mathbf P _{k|k}\), which will be used for estimating a priori parameters in the next time step \(k+1\).

Filtering the feature vector \(\varvec{\vartheta }\) using a Kalman Filter before classifying the perturbation force directions allows to overcome two issues. First, the feature vector \(\varvec{\vartheta }\) is often very noisy and leads to some misclassification cases [see Gómez-Eguíluz et al. (2017b)]. More importantly, using \(\varvec{\vartheta }\) as descriptor for perturbation force directions results in occasional false positives which trigger the hand to release the grasp, allowing the object to fall. By filtering the angular deviation of the contact forces abrupt changes in the trajectory estimation of the angles deviation that put the safety of the object at risk will not occur; for instance, when the object perturbation force has ended, a bouncing effect might happen after sudden release. Secondly, by computing the posterior state of the observation we estimate the angular deviation velocity \(\dot{\varvec{\vartheta }}\) of the contact forces, which provides additional information to enhance classification accuracy with respect to our baseline work.

2.5 Statistical learning of perturbation force directions

Object release detection is based on two events: the change in the perceived load force (see Sect. 2.3), and the issue of a pulling force by the receiver with a predetermined direction. The classification of the pulling force direction applied on the object is characterised as follows. We denote H as the discrete random variable representing the different perturbation force directions in the fingertip reference frame (E) relative to the stable grasp measured in azimuth and elevation, i.e. the n events to be identified \(\{h^1,h^2,\ldots ,h^n\}\), and \(\hat{\mathbf{X }}\) the 12-dimensional random vector of features encoding the posterior state estimate through the Kalman filter. In this case the number of object perturbation forces is \(n=5\), corresponding to forward, backward, up and down perturbation directions and a receiver steady grasp event where no perturbation force is applied. We obtained training sets to estimate the likelihood functions of the feature vectors for each event, \(p(\hat{\mathbf{X }}|h^j)\), which we model as normal distributions \({\mathcal {N}}\left( \varvec{\mu },\varvec{\Sigma }\right) \) with mean \(\varvec{\mu }\) and covariance \(\varvec{\Sigma }\). Therefore, for each event j, we obtained a normal distribution with mean \(\varvec{\mu }^j\) and covariance \(\varvec{\Sigma }^j\).

Having the models of the likelihood function \(p(\hat{\mathbf{X }}|h^j)\) for all events and given a set of prior probabilities \(p(h^j)\), one can estimate, through the Bayes rule, the posterior probabilities \(p(h^j|\hat{\mathbf{X }})\), and classify input data according to the maximum a posteriori (MAP) probability. For simplicity, we will denote \(\hat{\mathbf{X }}_{k} = \hat{\mathbf{X }}_{k|k}\) the Kalman filter’s state estimate at time k. Under the assumption of initial uninformative priors \(p(h^j)=\frac{1}{n}\) for all pulling directions j we update the current estimate when the change of the load force \(\Delta {}^B\mathbf f _L\) exceeds a threshold \(f_{th}\) (see Sect. 2.3). Therefore we will use the feature vector \(\hat{\mathbf{X }}\) to iteratively obtain new posteriors for each event, and the posterior probability \(p(h^j_{k}|\hat{\mathbf{X }}_{k})\) at step k will be the prior to obtain the next estimate \(p(h^j_{k+1}|\hat{\mathbf{X }}_{k+1})\). When a significant change in the load force is first detected, the initial prior probabilities are distributed evenly among all events. We estimate the contact forces from the BioTAC data stream and compute the feature vector \(\hat{\mathbf{X }}_k\), in windows of time length \(\Delta t\), and update the posterior probabilities, when a significant variation in the load force is detected, using:

$$\begin{aligned} p\left( h^j_k|\hat{\mathbf{X }}_{k}\right)= & {} \frac{p\left( \hat{\mathbf{X }}_k|h^j_k\right) p\left( h^j_k|\hat{\mathbf{X }}_{k-1}\right) }{p\left( \hat{\mathbf{X }}_k|\hat{\mathbf{X }}_{k-1}\right) } \end{aligned}$$
(7)

where \(p(\hat{\mathbf{X }}_k|h^j_k)\) is given by the likelihood function of perturbation force direction \(h^j\), and the normalisation constant \(p(\hat{\mathbf{X }}_k|\hat{\mathbf{X }}_{k-1})\) can be obtained as:

$$\begin{aligned} p(\hat{\mathbf{X }}_k|\hat{\mathbf{X }}_{k-1})= & {} \sum _i^Np\left( \hat{\mathbf{X }}_k|h^i_k\right) p\left( h^i_k|\hat{\mathbf{X }}_{k-1}\right) . \end{aligned}$$
(8)

2.6 The reliable object handover algorithm

The pseudocode of the proposed approach for reliable object handover is shown in Algorithm 1. In each iteration the algorithm estimates the load force variations (line 5) and, if required, updates the conditional probability \(p(h^{j}_k|\hat{\mathbf{X }}_{k})\) for all perturbation events, \(j=1,\ldots , n\) (line 15). It is worth noting that there is an abuse of notation in the computation of the angular changes, since the perturbation angles are obtained from the normalised force vectors in lines 8 and 9 of the algorithm. The object perturbation force direction which has the highest posterior probability can be considered the one that the robot is perceiving at time step k. However, we aim to endow robots with a reliable method that guarantees reliable handovers. As mentioned before, a single false positive would result in the object falling. Hence, the proposed algorithm only releases the object if a pre-set pulling direction \(h^*\), i.e. direction in which the human is expected to pull the object, is detected during more than \(t_{th}\) seconds (lines 17–21). As the value of \(t_{th}\) is small (0.25 s), the system is still responsive enough to release the object in a timely manner (see Sect. 3.2). Although a small value of \(t_{th}\) also entails the detection of load force variations caused by unexpected collisions, they are detected as isolated events as collisions are not likely to be consistent during \(h^*\) seconds. Thus, the reliable object handover algorithm ensures the safety of the object by releasing only when the pulling force direction is consistent with the pre-set perturbation force direction for a period of time. As detailed in Sect. 2.1, the algorithm also ensures the safety of the object by maintaining the initial wrench (line 23) when perturbation forces are applied on the object.

figure e

3 Experimental results

This section presents a set of experiments performed to illustrate the workings of parts of our algorithm and to carry some proof-of-concept tests. Specifically, Sect. 3.1 shows how the pulling direction can be estimated with the features presented in Sect. 2.4 using the Kalman filter. Section 3.2 extends the tests to the detection of the discrete perturbation directions, and illustrates the procedure to find good parameters of the algorithm. Finally, Sect. 3.3 presents results from the overall algorithm including the release of the object once all the conditions of the algorithm are met, i.e. right perturbation direction and duration.

Fig. 4
figure 4

Experimental set-up

The algorithm presented was evaluated on a real Shadow Robot Hand with Syntouch BioTAC tactile sensors installed in the thumb, first and middle fingers. The Shadow Hand was attached to a Schunk arm modified to compensate for the additional weight. Figure 4 shows the experimental set-up used. Although the arm stays fixed in all of the experiments, the set-up provides a natural handover configuration by placing the hand horizontally. The initial configuration of the fingers was manually set in the centre of the hand workspace and we used it for all the experiments as a starting point for the initial grasping. This position allows large finger motions without lost of contact when perturbation forces are applied to the object. From this initial approximate position, the fingers were manually adjusted to generate a stable precision grasp on the object, and to apply a force within the range the BioTAC sensors can estimate. Therefore, every experiment had slightly different configurations of grasp forces applied on the object. Before performing the experiments the electrodes of the BioTAC were calibrated to avoid drifts of the readings due to changes in the sensor gel after a series of runs. In order to avoid damaging the robotic hand when applying a perturbation force, the grasp effort controller (see Sect. 2.1) was used during all the experiments. The effort controller adapts the contact forces online to the initial configuration and, thus, ensures the safety of the hand and the object. However, the effort controller interaction also makes the problem of detecting the object perturbation force direction more complex as the controller tries to restore the forces and reduce the perturbation.

Readings from four perturbation force directions were manually collected from examples to obtain models of their corresponding likelihood function (from the receiver’s perspective forward, backward, up and down). This experimental modeling methodology can be extended to other perturbation directions. All training data were obtained from the initial grasp configuration using a flex foam cube of size \(4.5\times 3.9\times 3.25\) cm with high stiffness, i.e. the maximum hand force cannot deform the object. The training data were stored when the variation of the load forces exceeds a threshold (\(f_{th} = 0.5\)) as the algorithm only computes the posterior probability of the perturbation force directions when this condition is met (see Sect. 2.3). This means that the number of training trials required varied for each perturbation class. The number of trials used to model each object perturbation force was typically between 5 and 10.

As mentioned in Sect. 2, the detection of pulling force directions relies on the variations of the contact force estimate of each finger. We experimentally found that a sequence of perturbations is often applied to the object by the human receiver of the handover instead of one pure pulling force direction. For instance, an unintentional perturbation force might be applied while approaching the grasp followed by an intentional one, which may not be in the same direction. Furthermore, we compute the likelihood function for a “joint grasp” state, i.e. robot and human, in which the perturbation forces might not be intentional or sufficiently significant to determine the perturbation force direction accurately. Although the system does not release the object when detecting this state, we found that it enhances the reliability of the handovers (see Sect. 3.2).

Together with the four force directions, we modelled the angle variations of all fingers when the object is grasped but non-intentional force was applied, i.e. a “joint grasp” state. In order to obtain a wider range of small force perturbations, we did not use the event detection system for collecting readings of the “joint grasp” state. Therefore, unlike training data from intentional perturbation forces, the data used for obtaining the models of the “joint grasp” state were sampled at fixed rate. This method resulted in collecting more data for each trial and, consequently, the number of trials used to model the “joint grasp” state was reduced to three.

Fig. 5
figure 5

Index finger angle variations during downwards perturbation force

3.1 Trajectory filtering

In this experiment a number of object perturbations were performed on a grasped object to understand the interaction of the Kalman Filter on the force angle variations with respect to the stable grasp reference. As explained in Sect. 2.4, the true state X is filtered to reduce the noise and to obtain additional hidden features, i.e. angle variation velocities. We evaluate the experiment on three foam objects with different geometries but similar stiffness: a cube, a cylinder and an octagon prism; and we used the initial grasping forces as the reference for the controller. A perturbation force was then applied to the object and the posterior \({\hat{X}}\) and true X force states were stored at every time step. Figure 5 shows the evolution of the angle variations, with and without filtering, and their corresponding velocities during a downward perturbation force. Figure 5a plots the azimuth angle variations of the index finger \(\theta _2\) and Fig. 5c represents the elevation angle variations \(\phi _2\) for the same finger. The solid lines represent the angular deviations of true force state X while the filtered angle trajectories, \({\hat{\theta }}_2\) and \({\hat{\phi }}_2\), are represented by dashed lines. Figure 5b, d show the velocity hidden state of the azimuth \(\dot{{\hat{\theta }}}_2\) and elevation \(\dot{{\hat{\phi }}}_2\) angles respectively i.e. obtained from the posterior force state \({\hat{X}}\).

In comparison with the approaches presented in Gómez-Eguíluz et al. (2017a, b), it can be observed that filtering the signal reduces the noise in X, smoothing the trajectory. Furthermore, it was found that smooth trajectories together with velocities simplifies statistical modelling and enables each perturbation to be modelled as a Normal distribution (see Sect. 2.5), while in previous works the perturbations were modelled as mixture of Gaussians. Hence, the presented approach eliminates the need to provide the number of Gaussians of each mixture model and allows one to effectively deal with occasional sudden changes in the object perturbation forces.

Fig. 6
figure 6

Recursive estimation of perturbation force directions

3.2 Object perturbation detection experiments

This section presents the experimental results of the approach presented in Sect. 2 for detecting object perturbation force directions. For this set of experiments a total of 48 trials were collected from four different object perturbation force directions and 12 additional trials of “joint grasps”, i.e. no intentional perturbation forces applied, using three objects: a cube, an octagon prism and a cylinder. For all data collection, the initial grasp configurations were manually adjusted to generate an initial stable grasp approximately similar in all trials. This led to slightly different grasp configurations and applied forces over the objects. The variations in initial grasp configurations are not the only differences between trials, since the object pulling forces were not controlled and the iteration of the grasp effort controller varies across trials. Figure 6 shows the classification estimate for 1 s long perturbation forces in forward, upwards and downwards directions. Although the initial estimate might be incorrect, the system always estimates the correct perturbation direction when sufficient evidence is presented. This demonstrates that the system can generalise to unseen object shapes as the cylinder or the octagon prism were not used for training. Moreover, it can be observed that the largest estimated probability remains stable after the correct perturbation force direction has arisen.

As explained in Sect. 2.6, the reliable object handover algorithm detects that the receiver is pulling the object in a certain direction when its estimate is higher than any other direction estimate during \(t_{th}\) seconds. Therefore, the value of \(t_{th}\) establishes a trade-off between system responsiveness and classification accuracy. The aim is to find a value of \(t_{th}\) that guarantees that the system will perform reliable handovers. This is discussed in the next section.

3.2.1 Response versus accuracy

In this experiment the time required for successful identification of the correct perturbation for different values of \(t_{th}\) seconds using the 48 trials from four different perturbation force directions detailed above is computed. The time needed to detect the “joint grasp” state is not considered as the proposed algorithm only computes a new estimate of perturbation force directions if a significant change on the load force is detected. This makes it impossible to replicate similar conditions with the whole algorithm running as the data used for modelling a “joint grasp” were collected without using the event detection system. Furthermore, considering that the handover should never be completed during the detection of a “joint grasp” state, the time needed to detect it would not be representative of the system responsiveness for object release.

Figure 7 shows the average time needed for successful identification \(\mu \) and standard deviation (\(\sigma \)) for different values of \(t_{th}\) since the perturbation force is first applied on each trial used in this experiment. It is worth noting that there is a lower boundary of identification time as perturbations are detected when the estimate is consistent during a period longer than \(t_{th}\) seconds. Therefore, the minimum time that detecting the correct perturbation can take is \(t_{th}\) seconds and it is represented as by a red dotted line (see Fig. 7). The solid line represents the average time needed for successful identification while the average value plus three times its standard deviation \(\mu + 3\sigma \) is represented by the dashed line, showing the range in which successful object perturbation force detection is performed \(99.7\%\) of the times. We found that, despite the average detection time growing progressively with increasing \(t_{th}\), the standard deviation significantly increases for values greater than 0.25. It can be concluded that, although the value of \(t_{th}\) should remain as small as possible, good response is achieved for values smaller than 0.25, for which the detection seldom takes longer than 0.4 s.

Fig. 7
figure 7

Identification speed for different values of \(t_{th}\)

Fig. 8
figure 8

Identification accuracy for different values of \(t_{th}\)

Additionally, the average classification accuracy of the proposed approach for different values of \(t_{th}\) is analysed using the same 48 trials from four different object perturbation force directions used in the rest of experiments of this section. Differently than when evaluating the time required for successful identification, this experiment considers the 12 additional trials of “joint grasps” as their misclassification could result in unexpected object release. Figure 8 shows the average accuracy as a function of \(t_{th}\). We found that an \(81.57\%\) identification accuracy is obtained when only one estimate is considered, i.e. \(t_{th}=0\), being significantly increased when using greater values of \(t_{th}\). In order to choose an appropriate value for \(t_{th}\), one could choose the value such that greater values do not significantly increase the classification accuracy. According to that criterion, a \(95.29\%\) identification accuracy was obtained when selecting \(t_{th}=0.15\).

Table 1 Confusion Matrix of perturbation force directions for \(t_{th}=0.15\)

3.2.2 Tuning for reliable handovers

In practice a reliable handover system should never release the object when it is not supposed to. Although the results of the previous experiment show that \(t_{th}=0.15\) provides the best trade-off between system responsiveness and classification accuracy, the aim is also to keep the rate of false positives as low as possible. Table 1 shows the confusion matrix of perturbation force directions for \(t_{th}=0.15\) which, as mentioned above, provided the best trade-off between system responsiveness and classification accuracy. Despite the average classification accuracy being \(95.29\%\), one can understand that trials classified as “joint grasp” will not make the system fail as the object will not be released on this state. However, it is fair to say that it makes the system less responsive, as detecting the “joint grasp” state while a perturbation force in the direction set for object release is being applied will delay the completion of the handover. Therefore, the system will find a false positive \(1\%\) of the times for \(t_{th}=0.15\), which may result in unexpected object releases. Nevertheless, this limitation can be overcome by increasing \(t_{th}\) at the cost of reducing the system responsiveness. As mention in Sect. 3.2.1, the system response is not significantly decreased for values of \(t_{th} < 0.25\) s. The confusion matrices for different values of \(t_{th}\) were computed and it was found that the number of false positives for all values greater than 0.20 s is zero. Table 2 shows the confusion matrix for \(t_{th}=0.25\) in which only the values belonging to the diagonal or the “joint grasp” are different from zero. It is worth noting that \(t_{th}=0.25\) maintains good system responsiveness as the average time needed for successful identification is 0.27 s (see Fig. 7). Therefore, \(t_{th}=0.25\) provides adequate balance between average accuracy (\(96.77\%\)), average responsiveness (0.27 s) and system reliability (\(0\%\) false positives).

Table 2 Confusion Matrix of perturbation force directions for \(t_{th}=0.25\)

3.3 Force adaptation and object handover

This section presents experimental results of the reliable handover algorithm when a sequence of perturbation forces with different directions are applied to the object. Specifically, we performed force direction detection experiments along with the effort adaptation controller for sequences of two combined perturbations. Therefore, the response of the approach was tested using a variety of consecutive events including at the end a perturbation force that was pre-set to be the direction that completes the handover, i.e. the hand has to open the fingers releasing the object. We evaluated the algorithm for every combination of perturbing forces such as two opposite object rotations, vertical forces, pushing and pulling (from the user viewpoint), while the robot is expected to perform a handover only when the backward perturbation is detected, i.e. the human pulls from the object.

Fig. 9
figure 9

Object rotation and pulling event sequence

Figure 9 shows the sequence of one of the trials, where the object is rotated in a counter-clockwise direction and then pulled from the robot hand, i.e. triggering the object release. Although the fingers adapt individually and the controller has no information on the shape of the object, the system kept contact with the object and maintained a stable grasp when rotating the object (see Fig. 9b, c). Then, the object was released when a perturbation force backwards was detected as shown in Fig. 9d–f.

Fig. 10
figure 10

Forces response against object rotation and pulling events for each finger

Figure 10 shows the evolution of the components of the forces over time in their corresponding end-effector frame for the above experiment. The first two solid vertical lines in the time sequence represent the start and end of the object rotation and were set using the event detection system. The third vertical line sets the beginning of the pulling force perturbation while the final vertical line signals the pulling force and consequent object handover. During a perturbation force, the contact forces deviate from the initial configuration and the fingers change their position while trying to keep the difference with the reference forces as small as possible. When the perturbation force ends the controller keeps trying to restore the reference contact forces. However, the hand could not generate the exact same forces since the configuration of the fingers changed and the robot did not have enough degrees of freedom to compensate for these variations. This happens in many trials because each finger has only three joints and therefore the grasping configurations were not manipulable. Nonetheless, the controller maintained the forces close to the initial reference and, despite the fact that the configuration of the hand changed after the first perturbation, the proposed approach successfully detected the pulling event and released the object.

Fig. 11
figure 11

Perturbation on object classification of a sequence of events

We tested the performance of the continuous detection of perturbation force directions in the current experiment. Figure 11 plots the results of the classification for the time periods in which the object perturbations are applied which corresponds to the time periods of Fig. 10 from 2–3.3 s and 5.5–8.2 s. The horizontal axis is the time while the vertical axis is the probability of each direction. A solid vertical line shows the exact moment when the correct force perturbation is detected i.e. consistent estimation during more than 0.25 s. As the algorithm only computes the posterior estimates of the perturbation events when a change in the load force is detected, the classification is not performed at a fixed rate. Therefore the temporal gaps in Fig. 11 are a result of the overall force change being smaller than the threshold at that point. It is worth noting that, although the object rotations were not included in the training sets, the system was able to correctly classify an object perturbation force being applied upwards when rotating the object counter-clockwise. We found that intermediate object perturbation force directions were detected for a short period of time, prior to the detection of the correct one. Moreover, Fig. 11a shows a sequence of posterior estimates when the object was released from the roll rotation. Interestingly, this sequence of estimates is an inversion of the one observed prior to the detection of a perturbation upwards. However, none of these sequences of estimates kept a consistent estimate for longer than \(t_{th}=0.25\) s and, thus, they did not result in an object release. Figure 11a, b show that only the probability of the correct force direction is consistently estimated sufficiently long enough to be detected and, if required, triggered the object release (see Fig. 11b).

4 Conclusions and future work

This paper presents an algorithm to perform reliable robot to human object handovers, which has been implemented using a Shadow Robot Hand equipped with BioTAC tactile sensors. State-of-the-art approaches assume the handover is going to take place with no potential problem. However this is not always the case as external forces could be applied on the object during the handover process, resulting in the object falling or the robot hand being damaged. To solve these two issues, the proposed approach adapts the grasping with respect to perturbation forces on the object and only releases the object when the receiver pulls the object in a pre-set direction. Relying on tactile sensing, the proposed algorithm combines effort joint control, event detection, and identification of object perturbation force directions in order to perform reliable handovers.

Experiments show that the effort controller successfully adapts to new configurations in the presence of perturbations. However, the limited number of degrees of freedom of the fingers relative to the palm restricts the object movement. In the case of the Shadow Robot hand this implies small changes on the point of contact between the fingers and the object, which potentially affect the stability of the grasp. Although levels of variability on the contact force configuration for grasping the object were considered, objects with significantly different shapes might require additional training to deal with the resultant object grasps; e.g. when handing over a triangle. In general the parameters of the algorithm (pulling direction and force and time thresholds) could depend on the human and the handover context, so that they have to be optimised for individuals, groups or contexts. Tuning these parameters is in general not trivial, although the approach followed in this work, i.e. obtaining them from controlled experiments, could be generalised to other configurations. However, the pulling direction could be identified from the specific interaction scenario and converted into the (configuration dependent) fingertip reference. Future research will focus on further investigation into the human–robot interaction scenario to predict the direction in which the receiver is going to pull the object during the handover and with which strength. Visual information could be included prior to the handover to analyse the context in which it is going to be performed such as receiver’s height, pose, approaching hand, or intended object use. Although handovers typically occur during stationary situations, we also aim at implementing the proposed approach in mobile platforms and exploring the effects of other type of perturbations such as inertial and Coriolis forces.