Introduction

With continuous advancements in robot technology, service robots designed to assist or provide care to humans have become widely adopted [23]. Human body massage, a common nursing procedure with wide applications in medical care, can be tedious and time-consuming. The prolonged fatigue experienced by operators can lead to a decline in the quality of nursing care. Compared to manual operation, autonomous robotic massage systems can perform massage procedures, relieving operators of routine tasks and enhancing nursing efficiency while reducing labor costs [14]. However, achieving precise trajectory tracking on the human body by the robotic end-effector and ensuring safe operation through monitored and controlled contact force with the human body pose substantial challenges [15]. The unknown precise location and geometry of the human body further complicate the achievement of autonomous robotic massage on a human body.

Several robotic systems have been developed to perform massage tasks, involving physical interaction between the robotic end-effector and the human body. Research conducted by Wang et al. [28] designed a wheeled robot to move on the human body, utilizing an electromagnetic drive mechanism to achieve tapping motion. However, this method lacks motion stability and is susceptible to disturbances from the wheels. Luo et al. [18] employed a humanoid robot with two arms to perform massages by manipulating the velocity and acceleration of the robot end-effector, resulting in impulse contact and adaptive force alterations in Cartesian space. Nonetheless, their work does not consider the dynamics of the environment. To address this, Hu et al. [9] applied a multi-finger gripper to execute massage tasks, considering the kinematics and force characteristics of various massage movements such as rolling, kneading, and pressing [31]. Another study conducted by Xing et al. [29] developed a flexible back massage robot composed of a flexible silicone material integrated with a corrugated airbag. The safety of their system was ensured through passive compliance control.

A prerequisite for implementing automatic robot massage involves planning massage trajectories on the human body. Traditionally, two methods are commonly used for trajectory planning: learning-by-demonstration and remote control. For example, Liu et al. [16] proposed a learning-by-demonstration approach that allows a robot to record and replay human demonstrations. However, directly applying these demonstrated trajectories to new tasks or human bodies is challenging due to the significant variations between individuals. To overcome this limitation, Girbés-Juan et al. [8] used teleoperation techniques with force feedback to guide a robot to perform surface wiping tasks. The master/slave mode of operation in teleoperation lacks a view of the target object and often has a noticeable delay. To address these issues, more recent studies have employed visual data to plan massage trajectories. Hu et al. [10] utilized trained neural networks to estimate human posture and identify key anatomical landmarks on the human back, which were then used as navigation points for the robot. However, their method treated the human back as a 2D plane, and only 2D waypoints were planned accordingly. In contrast, Huang et al. [11] utilized a 3D point cloud of the human body to automatically plan trajectories by segmenting the object contour based on pixel color criteria. Their work addressed the 3D trajectory planning problem based on visual data. But, the preferences of operators, especially paramedics, were not taken into account.

Fig. 1
figure 1

Overall workflow of the proposed VBRM framework

During the massage, human body movement may occur, resulting in a deviation from the intended course. Consequently, it is necessary to monitor human body movement during robot massage. The two categories of movement tracking methods are marker-based tracking and marker-less tracking [5]. By detecting optical markers placed on the human body, Jiang et al. [12] monitored changes in the planned trajectories. However, the cumbersome arrangement of optical markers adds complexity to the system, making its widespread adoption challenging. Usually, the overall movement of the body during a massage is simple, thus visual methods can be used to track human motion and adjust the planned trajectory. The Iterative Closest Point (ICP) algorithm [22], which uses the point cloud for global registration, is exemplary of rigid point cloud registration techniques. A method of dynamic fusion [21] that detects non-rigid deformation reconstructs the input scene into a frame to detect surface deformation. However, the rigid deformation of the human body, which includes translation and rotation, is more worthy of consideration. The rigid ICP algorithm is superior compared with the non-rigid method in robot massage, because it is effective even when a portion of the surface is obscured.

Automatic robot massage requires precise tracking of the planned trajectory on the human body. Various trajectory tracking techniques, such as feedback control, visual servoing, and dynamic programming, have been developed in robotics [27]. Angelini et al. [2] used feedback control to make the soft robot accurately follow the predetermined trajectory. Garcia et al. [7] tracked moving objects with a seven-DOF robot using direct visual servoing. Visual servoing can produce a smooth velocity of the robotic end-effector by calculating the position error [26]. In addition to the position control of the robot’s end-effector, the contact force control of the robot has also been investigated. For automatic robot massage, safety and compliance requirements are crucial [30]. Therefore, it is prudent to avoid using excessive contact force. Luo and Hsieh [17] implemented a Cartesian-based impedance control to permit a dual-arm robot to perform a tapping motion on the human back. Dyck et al. [6] applied a passivity-based impedance control scheme so that it could interact with arbitrary surfaces. To achieve robot massage, the proposed controllers not only ensure the robotic end-effector tracks the desired trajectory but also ensure the contact force converges to the desired force.

In this study, we propose a novel framework named vision-based robotic massage (VBRM) for automating massage tasks on the human body. The framework utilizes a depth camera to capture RGB images and point clouds of the human body. A dynamic 3D massage trajectory is planned based on the operator’s preferences, and the robot is guided along this trajectory using visual feedback. A force control algorithm, which relies on force estimation, is employed to adjust the contact force between the robotic end-effector and the human body. The effectiveness of the proposed VBRM framework is demonstrated through real-world experiments. The contributions of this work can be summarized as follows:

  • Development of an interactive trajectory planning method for automatic robot massage that calculates the 3D massage trajectory from a 2D line drawn by the human operator. This method combines the operator’s preferences with trajectory planning to generate arbitrary massage trajectories.

  • The position and contact force of the robot’s end-effector is adjusted using a hybrid motion/force controller. This controller dynamically reduces the position error of the robotic end-effector to ensure accurate trajectory tracking, even if the position of the human body changes. Additionally, adjusting the contact force within an acceptable range enhances operational safety.

  • We validate the proposed VBRM framework using a real robot platform. The experimental results demonstrate the robot’s capability to perform massage operations on the human body.

This paper is organized as follows. Section “System overview” gives an overview of the proposed robotic massage system. Section “Interactive trajectory planning” introduces the method of interactive trajectory planning. Section “Robot control strategy” introduces the proposed hybrid motion/force controller. The contact force is estimated for robot motion control. Experimental results are presented in section “Experiment”. And lastly, the conclusion and future work are described in section “Conclusion”.

System overview

To achieve automatic robot massage, we propose a vision-based robotic massage framework (VBRM) that adjusts the posture and contact force of the robotic end-effector based on the planned trajectory.

System platform

(1) System hardware The proposed VBRM consists of a Baxter robot, a 3D-printed massage tool, and an RGB-D camera. The Baxter robot has two redundant arms with seven degrees of freedom each. The 3D-printed massage tool is attached to the left arm’s end-effector. The RGB-D camera is mounted on the Baxter robot to capture the visual information of the human body. The proposed approaches are built up with Python on an Ubuntu system.

(2) Workflow The overall workflow of the proposed VBRM includes three computational steps: (1) an interactive trajectory planning with human guidance, (2) a movement tracking method for trajectory update, and (3) a hybrid motion/force controller for performing massage operations on the human body (Fig. 1). First, the camera captures the visual information of the human body, including the RGB image, depth image, and point clouds, as the input of the VBRM. On the RGB image, a human operator draws a 2D massage trajectory. The 2D trajectory is then projected based on the visual projection to calculate the 3D massage trajectory in the robot’s coordinate system. Once the human body moves, the proposed movement tracking algorithm updates the massage trajectory online by calculating the transformation matrix of the human posture. Lastly, the robot automatically follows the dynamic trajectory with a hybrid motion/force controller while maintaining the desired contract force on the human body.

System calibration

The calibration of the VBRM framework is performed before trajectory planning. The homogeneous transformation matrix is used to describe the coordinate relationship between the robot, camera, and human body. As depicted in Fig. 2, the involved coordinate frames are as follows: (1) the robot base frame \(\{b\}\), (2) the RGB-D camera frame \(\{c\}\), (3) the color image pixel frame \(\{p\}\), (4) the robotic end-effector frame \(\{e\}\), and (5) the trajectory frame \(\{t\}\).

Fig. 2
figure 2

Diagram of the coordinate frames

Based on the kinematic model of the Baxter robot, the transformation \({_e^b}T\) from the \(\{e\}\) to the \(\{b\}\) can be computed. The transformation \({_c^b}T\) between the \(\{b\}\) and \(\{c\}\) is established based on camera extrinsic calibration. In this work, we use a least square calibration method based on singular value decomposition (SVD) [25] to calculate the \({_c^b}T\). In particular, the robot is controlled by moving its end-effector to generate a set of calibration data, where a marker is mounted onto the end-effector. The motion trajectories of the end-effector and marker, i.e., \(P^m=\{p^m_1,p^m_2,\ldots , p^m_n\}\) and \(P^e=\{p^e_1,p^e_2,\ldots , p^e_n\}\), are recorded. Figure 3 shows the collected trajectory points of the end-effector and marker. To establish the connection between \(P^m\) and \(P^e\), a covariance matrix \(M_{\textrm{cov}}\) between \(P^m\) and \(P^e\) is defined as:

$$\begin{aligned} M_{\textrm{cov}} = XW{Y}^\top \end{aligned}$$
(1)

where W is a diagonal matrix with weighting, and X and Y are matrices with columns \(x_i\) and columns \(y_i\), respectively. \(x_i=p^m_i -\bar{p}^m,y_i=p^e_i-\bar{p}^e\) denotes the centered vector of the \(P^m\) and \(P^e\). \(\bar{p}^m\) and \(\bar{p}^e\) represent the average of trajectory points.

Fig. 3
figure 3

Illustrated of camera extrinsic calibration. The trajectory points (green) of the marker are registered to the trajectory points (red) of the robotic end-effector

Then, the \(M_{\textrm{cov}}\) is decomposed by using SVD to produce three matrices to satisfy \(M_{\textrm{cov}}=UDV\), where D is a diagonal matrix, U and V depend on \(M_{\textrm{cov}}\). As a result, the transformation \({_c^b}T\) is calculated by combining the rotation matrix R and the translation matrix T as follows:

$$\begin{aligned} _c^bT = \begin{bmatrix}R &{}\quad T\\ 0 &{}\quad 1\end{bmatrix} \end{aligned}$$
(2)

with

$$\begin{aligned} R = cV\begin{bmatrix}1&{}&{}\\ &{}\quad 1&{}\\ &{}&{}&{}\quad \text {det} (V{U}^\top ) \end{bmatrix}{U}^\top \end{aligned}$$
(3)

and

$$\begin{aligned} T = \bar{p}^m-R\bar{p}^e \end{aligned}$$
(4)

where c is a positive coefficient. Once the transformation \({_c^b}T\) is determined, the transformation \({_e^c}T\) from the \(\{e\}\) to the \(\{c\}\) can calculate by \({_e^c}T = {_b^c}T {_e^b}T\)

Interactive trajectory planning

This section introduces the interactive trajectory planning method for generating 3D massage trajectories on the human body. Besides, the possible movement of the human body is monitored with an ICP algorithm to online update the planned trajectory.

Fig. 4
figure 4

Projection principle. 2D-pixel frame map to 3D camera frame, the camera captures the human body model

Calculation of 3D massage trajectory

To plan the arbitrary trajectory, the human operator draws the desired massage trajectory as a 2D curve on the RGB image of the human body (Fig. 1). The 2D trajectory is then projected to generate the 3D trajectory points relative to the base frame \(\{b\}\). Figure 4 shows the perspective projection model of the camera. From the 2D curve, we sample the pixel points \(\overrightarrow{Q}=\{q_1,q_2,\ldots ,q_n\},~q_i\epsilon \mathbb {R}^{2}\) w.r.t. the \(\{p\}\), where \(q_i= (u,v) \) is the 2D coordinate in the image plane. The projected 3D points are denoted as \(\overrightarrow{P}=\{p_1,p_2,\ldots ,p_n\},~p_i\epsilon \mathbb {R}^{3}\) w.r.t. the \(\{c\}\), where \(p_i= (x_c,y_c,z_c) \) the 3D coordinate in the \(\{c\}\). Reference to [13], the relationship between the 3D trajectory point \(p_i\) and the 2D point \(q_i\) is given as follows:

$$\begin{aligned} D_c\begin{bmatrix}u\\ v\\ 1\end{bmatrix} = \begin{bmatrix}1/\textrm{d}x&{}\quad 0&{}\quad u_0\\ 0&{}\quad 1/\textrm{d}y&{}\quad v_0\\ 0&{}\quad 0&{}\quad 1\end{bmatrix} \begin{bmatrix}f&{}\quad 0&{}\quad 0\\ 0&{}\quad f&{}\quad 0\\ 0&{}\quad 0&{}\quad 1\end{bmatrix} \begin{bmatrix}x_c\\ y_c\\ z_c\end{bmatrix} \end{aligned}$$
(5)

where \(D_c\) is the depth information obtained from the captured depth map, \(u_0\) and \(v_0\) are the coordinates of the principal point. \(\textrm{d}x\) and \(\textrm{d}y\) are the actual physical size of the pixel and f is the focal length.

Using the calculated 3D trajectory points \(\overrightarrow{P}\), we fit the 3D trajectory points with the least squares B-spline curve. Before data fitting, the 3D trajectory is smoothed by the following steps: (1) We down-sample the raw point clouds and use the random sample consistency algorithm to segment the human body point clouds from the scene point clouds; (2) a nearest neighbor search method [19] is applied to the trajectory points \(\overrightarrow{P}\), and the principle (Fig. 5). The trajectory \(\overrightarrow{P_c}\) is fitted using the B-spline curve. The fitted result represents the desired robot trajectory, denoted as \(\overrightarrow{P_d}=\{p_{d1},p_{d2},\ldots ,p_{dn}\},~p_{di}\epsilon \mathbb {R}^{3}\), as shown in Fig. 5.

Fig. 5
figure 5

The process of trajectory generation. In the neighbor search field of \(p_i\), add a \(p_c^i\) with smaller \(\Delta d_i\) to \(\overrightarrow{P_c}\). using B-spline to fit \(\overrightarrow{P_c}\) to produce a trajectory

Online trajectory update

Possible movement of the human body may occur during the massage, resulting in a deviation from the intended trajectory. To address the dynamic of the environment, this work proposes tracking the human body’s movement and updating the 3D massage trajectory. The point clouds of the human body are used as inputs for movement tracking. \(X_m=\{x_1,x_2,\ldots ,x_n\}\) and \(P_m=\{p_1,p_2,\ldots ,p_n\}\) denote the human body’s point clouds at the previous and current time steps, respectively. We establish the pose transformation between two point sets using the ICP algorithm. In the process of cycle detection, the difference between the two point sets is represented as follows:

$$\begin{aligned} E (R, t) =\frac{1}{N_{\textrm{p}}} \sum _{i=1}^{N_{p}}\left\| \bar{x}_{i}-R \bar{p}_{i}-t\right\| ^{2} \end{aligned}$$
(6)

where \(N_p\) represents the number of points in the point cloud, R represents the rotation matrix, and t represents the translation vector.

Calculate the transformation matrix between two point sets by minimizing the error E(Rt) . However, if the number of points between two point clouds is not equal, the fitting error will occur. The translation vector t and the rotation angle \(\theta \) of the transformation matrix are accepted as evaluative criteria as \(s (t, \theta ) \), where \(\theta \) is defined as follows:

$$\begin{aligned} |\theta |=\arccos \left( \frac{{\text {tr}} (R) -1}{2}\right) \end{aligned}$$
(7)

where \(\text {tr} (R) \) represents the sum of the diagonal elements of R.

Using the evaluative criterion \(s (t, \theta ) \) the massage trajectory \(\overrightarrow{P_{\text{ r } }}\) could be dynamically updated if \(s (t, \theta ) \) is greater than the threshold value.

The updated desired trajectory \(\overrightarrow{P_\textrm{u}}\) is given by:

$$\begin{aligned} \overrightarrow{P_\textrm{u}}=\left( R \overrightarrow{P_\textrm{d}}+t\right) \end{aligned}$$
(8)

where \(\overrightarrow{P_\textrm{d}}\) represents the last desired trajectory here.

Robot control strategy

This section introduces a hybrid motion/force controller for the VBRM to control the motion of the robot end-effector and the contact force between the end-effector and the human body. Figure 6 shows the schematic of the proposed controller. A position-based visual servoing (PBVS) algorithm is used to reduce the tracking error of the robotic end-effector dynamically. To ensure safe operation, the normal contact force between the end-effector and the human body is adjusted.

Fig. 6
figure 6

Hybrid controller for automatic robot massage

Trajectory tracking based on visual servoing

The visual servoing algorithm [4] is used to control the end-effector of the robot so that it follows the planning trajectory. The motion velocity of the end-effector is adjusted according to the tracking error. The tracking error is defined as the distance between the desired and actual poses of the end-effector:

$$\begin{aligned} e = f_{e} - f_{d} = \left( { }^{e} t-{ }^{d} t,{ }^{e}\theta {}^{e}u-{ }^{d}\theta {}^{d}u\right) \end{aligned}$$
(9)

where a feature \(f= (t,\theta u) \), t is the translation vector, and u is the unit eigenvector of the 3D rotation matrix corresponding to eigenvalue 1, \(\left| \theta \right| \) is the rotation angle depending on u.

During the approach of the end-effector to the target, the velocity \(v_e\) is calculated as follows:

$$\begin{aligned} v_{e}=-\lambda \widehat{L_{e}^{-1}} e \end{aligned}$$
(10)

where \(\lambda \) is a proportional gain matrix and \(\widehat{L_{e}^{-1}}\) is the pseudo-inverse matrix of the interaction matrix [3], defined as follows:

$$\begin{aligned} \widehat{L_{e}^{1}}=\left[ \begin{array}{cc} -I_{3} &{}\quad {\left[ { }^{b} P_{e}\right] _{x} {L_\theta }_u^{-1}} \\ 0 &{}\quad {L_{\theta }}_u^{-1} \end{array}\right] \end{aligned}$$
(11)

with

$$\begin{aligned} L_{\theta u }=I_{3}-\frac{\theta }{2}[u]_{\times }+\left( 1-\frac{\sin c \theta }{\sin c^{2} \frac{\theta }{2}}\right) [u]_{\times }^{2} \end{aligned}$$
(12)

where \(I_3\) is the 3\(\times \)3 identity matrix.

The velocity \(v_e\) is a volume that changes with error. With continuous tracking points, this will make it difficult for the robot to maintain a stable speed. To address this issue, we propose a method for compensating the end-effector velocity based on position information in the X-O-Y frame. The compensation velocity \(v_c\) is given by:

$$\begin{aligned} v_{c}=\left[ \begin{array}{cc} x &{} -x_{l} \\ y &{} -y_{l} \end{array}\right] \left[ \begin{array}{l} 1 / \textrm{d}t \\ 1 / \textrm{d}t \end{array}\right] \end{aligned}$$
(13)

where \(\textrm{d}t\) is a scale factor to adjust velocity. (xy) and \( (x_l,y_l) \) denote the current and last desired position of the end-effector, respectively. Then, the two computed velocities \(v_e\) and \(v_c\) are combined together as \(v_s\):

$$\begin{aligned} v_{s}=v_{e}+\left[ \begin{array}{c} v_{c} \\ 0 \end{array}\right] \end{aligned}$$
(14)

Regulation of normal contact force

To ensure the safety of robot massage, the normal contact force must be monitored and adjusted to prevent excessive contact force. First, the contact force estimation is performed based on joint torques. The contact force relative to the joint torques can be described with the Jacobin matrix [20] as follows:

$$\begin{aligned} F=\widehat{\left( {J}^\top \right) ^{-1}} \tau \end{aligned}$$
(15)

where \(\tau =\left[ \tau _{1}, \tau _{2}, \ldots , \tau _{7}\right] \) represents the torque of the robotic joints, F represents the normal contact force of the end-effector, and J is the Jacobian matrix of the Baxter robot arm as previously described.

In this work, the Z-direction motion velocity of the robotic end-effector is adjusted according to the force error \(e_\textrm{f}\). The force error \(e_\textrm{f}\) is calculated by subtracting the estimated contact force \(F_\textrm{e}\) from the desired contact force \(F_\textrm{d}\), i.e., \(e_\textrm{f}=F_\textrm{e}-F_\textrm{d}\). This work employs a Proportional-Integral-Derivative (PID) controller [1] for force control. The desired Z-direction motion velocity \(e^f_z\) as follows:

$$\begin{aligned} v_{z}^{f}=K_\textrm{p}\left[ e_\textrm{f} (t) +\frac{1}{T_{i}} \int _{0}^{t} e_\textrm{f} (t) \textrm{d} t+T_\textrm{d} \frac{\textrm{d} e_\textrm{f} (t) }{\textrm{d} t}\right] \end{aligned}$$
(16)

The following relationship exists between a velocity \(v_z^f\) with force control and a velocity \(v_s\) with visual servoing:

$$\begin{aligned} v_{\text{ robot } }=v_{s} S+v_{z}^{f} \bar{S} \end{aligned}$$
(17)

with

$$\begin{aligned} S=\left[ \begin{array}{lll} I_{2} &{} &{} \\ &{}\quad 0 &{} \\ &{} &{}\quad I_{3} \end{array}\right] \end{aligned}$$
(18)

where \(I_2\) and \(I_3\) are respectively a 2\(\times \)2 identity matrix and a 3\(\times \)3 identity matrix.

As a result, the robot system is controlled in joint space, the joint velocity \(\dot{q} \) is calculated as follows:

$$\begin{aligned} \dot{q}=\widehat{J^{-1}} v_{\text{ robot } } \end{aligned}$$
(19)

where \(\widehat{J^{-1}}\) is a pseudo-Jacobian matrix representing the Baxter robotic arm [24].

Experiment

This section begins with a performance evaluation of the interactive trajectory planning method. Then, using real-world experiments, the effectiveness of the proposed VBRM framework is demonstrated. The experimental results and their analysis are provided.

Fig. 7
figure 7

Experimental setups of interactive trajectory planning

Validation of interactive trajectory planning

To verify the performance of the proposed trajectory planning and updating methods described in section “Online trajectory update”, the positioning accuracy experiments in static and dynamic scenarios were carried out. The experimental setups are shown in Fig. 7. The board was in the same area as the object being wiped, approximately 60 cm away from the robot in the right arm working area of the Baxter robot. Nine augmented reality Alvar markers were divided into three groups to simulate the human back. Using a Kinect camera, the RGB images and point clouds of the scene were captured. An operator manually drew 2D points at the center of each marker in the RGB image. From the 2D points, the proposed planned method was then used to calculate the corresponding 3D points, denoted as \(P_i^c\). The 3D location of the marker was detected Using the open source AR tag tracking library,Footnote 1 denoted by \(P_i^r\). As a metric for evaluation, the difference \(e_{tp}\) between \(P_i^c\) and \(P_i^r\) is used, i.e., \({e_{t}}_p=\left\| P_i^c - P_i^r \right\| \).

Fig. 8
figure 8

Results of the trajectory planning method. a The error of the trajectory planning method, green dots are mean error. b The calculated 3D points were found in the point cloud (blue) and the 3D locations of the Alvar markers (red)

Fig. 9
figure 9

The experimental setup of robot massage

Fig. 10
figure 10

Results of robot trajectory tracking with different compensation velocity

Fig. 11
figure 11

Trajectory updating based on the ICP algorithm. a and c are results of trajectory tracking under translation and rotation motions, respectively. b and d are the results of the ICP algorithm for point cloud registration of translation and rotation motions, respectively

Figure 8 shows the results of interactive trajectory planning. The overall precision of trajectory planning is \(4.3 \pm 2.6\) mm. The mean absolute error in Euclidean coordinates for the near, middle, and far areas is \(2.2\pm 1.0\), \(4.54 \pm 2.7\), and \(6.29 \pm 4.2\) mm, respectively. The error increases with distance, but there is always a situation, as depicted by the red circle in Fig. 8b, in which the error is relatively large compared to other positions at the same distance. It can be seen that the depth of information is responsible for this significant error. Leaving aside these two positions with significant errors, the error of the remaining positions is \(2.78 \pm 1.19\) mm. Notably, while the mean error has a satisfactory value, the standard deviation is significantly larger than the mean error. This result is due to the discrepancy caused by the down-sampling of the point cloud, which prevents \(P_i^c\) from precisely reflecting the correct position data. In addition, the noise of the depth information and cloud points must be considered. Overall, the results show that the accuracy of the trajectory planning is adequate for the massage task.

Robot massage experiments

The effectiveness of the proposed VBRM framework was further evaluated with real-world experiments. Figure 9 shows the setup of real-world experiments, which include a Baxter robot and a model phantom. We designed a 3D-printed massage tool and attached it to the robot’s end effector. Soft glue was applied to the surface of the phantom to simulate human skin. The management software was executed on a Ubuntu computer with an Intel i7 processor.

Robotic massage without human movement

The purpose of static robot massage was to demonstrate tracking ability in standard conditions. The contact force was set to 6N with visual servoing and different compensation velocities as Eq. (13) to track the same trajectory. Figure 10 shows the tracking trajectory results of the VBRM system. The addition of compensation velocity can significantly reduce tracking time, as observed.

Robotic massage with human movement

During the robot massage, the model of the phantom was artificially translated and rotated to test the algorithm’s efficacy. As the trajectory was dependent on the transformation of the point cloud, the Root Mean Square Error (RMSE) of all inlier correspondences of point cloud registration was used as the experimental standard. The updated translation and rotation trajectories are depicted in Fig. 11. The inlier RMSE values for rotation and translation were 0.004 and 0.006, respectively.

The ICP algorithm used to track moving objects does not require labeling, so we can draw a line on the human model and move the end-effector along that line. The trajectory update frequency was set to 1Hz. During the end-effector motion, the human model is translated and rotated, respectively. In this experiment, we accounted for the target’s deformation and frictional force while it was in a contact and motion situation. We set the compensation velocity \(\textrm{d}t\) parameter to 0.5 and the desired force to a constant value of 6N. The result of trajectory tracking in dynamic environments is shown in Fig. 12. Excluding the associated robot end-effector movement caused by moving targets, it is possible to observe that the tracking error is generally small. The contact force performance in linear, sinusoidal, and circular trajectories is shown in Fig. 12b. From the experimental results, it can be seen that the proposed approaches can enable the robot to automatically execute the massage task.

Fig. 12
figure 12

Experiment result of ICP dynamic tracking with force controller

Conclusion

This paper thoroughly examines three crucial technical aspects of automatic robot massage: trajectory planning, dynamic trajectory tracking, and robot massage control strategy. We develop and evaluate a novel visual-based robot massage (VBRM) framework through real-world experiments. We calculate the 3D massage trajectory by projecting the human operator’s 2D line onto the RGB image. Our proposed interactive method satisfies user requirements for interactively planning arbitrary trajectories. By employing rigid point cloud registration, possible movements of the human body can be detected using a marker-free tracking method. Additionally, a hybrid motion/force control strategy is designed to adjust the motion of the robotic end-effector, ensuring the safety of the operation by avoiding excessive contact force. The efficacy of the proposed approaches is assessed through experiments, indicating that the proposed trajectory planning method effectively reduces planning time. Moreover, the results demonstrate the successful performance of the VBRM in executing the massage task.

For future development, the control strategy should incorporate a greater number of clinical cases, such as predicting human movement and identifying contact models. These enhancements will enhance the efficiency of the VBRM and bring it closer to clinical applications.