Tele-Operation and Active Visual Servoing of a Compact Portable Continuum Tubular Robot

Demo Videos

– tele-operation, visual servoing and hybrid control (Summery)

– EIH VS in free space – EIH VS inside a skull model

– Eye-to-hand Visual Servoing

Project goals

Trans-orifice minimally invasive procedures have received more and more attention because of the advantages of lower infection risks, minimal scarring and shorter recovery time. Due to the ability of retaining force transmission and great dexterity, continuum tubular robotic technology has gained ever increasing attention in minimally invasive surgeries. The objective of the project is to design a compact and portable continuum tubular robot for transnasal procedures. Several control modes of the robot, including tele-operation, visual servoing and hybrid control, have been proposed so that the robot is allowed to accomplish different tasks in constrained surgical environments.

Approaches

Driven by the need for compactness and portability, we have developed a continuum tubular robot which is 35 cm in length, 10 cm in diameter, 2.15 kg in weight, and easy to be integrated with a micro-robotic arm to perform complicated operations as shown in Fig. 1. Comprehensive studies of both the kinematics and workspace of the prototype have been carried out.
figsetup-2jbxtci
Fig. 1. Prototype of the proposed continuum tubular robot.
The workspace varies on different configuration of DOFs as well as the initial parameters of the tube pairs. The outer tubes in the following cases are all assumed to be dominating the inner tubes in stiffness. Calculation of the workspace relies on the forward kinematics of the robot, and considers the motion constraints imposed by the structure. The workspaces of the 4-DOF robot with three different initial configurations are compared in Fig. 2 (Left). Since the spatial workspace has rotational symmetry, only the sectional workspace is displayed.
fig2workspace         fig3-3dof
Fig. 2. Workspace comparison for 4-DOF CTR (Left) & 3-DOF CTR (Right) with three initial configurations. Top: all the outstretched part of the inner tube exposes; Middle: the outstretched part of the inner tube is partially covered by the outer tube; Bottom: the outstretched part of the inner tube is totally covered by the outer tube.
When the outer tube is straight, its rotation does not change either the position or the orientation of the tip. In this case, the robot degenerates to a 3-DOF one. Although decrease of DOF will weaken the dexterity of the robot, this configuration has its own advantages in some surgical applications. Take transnasal surgeries for example, as the nostril passage is generally straight, an unbent outer tube will facilitate the robot to get through at the beginning. Similar analysis of workspace is performed on the 3-DOF CTR with three different initial configurations, as shown in Fig. 2 (right). With different initial configuration, the workspaces also present different shapes.
In addition, tele-operation of the robot is achieved using a haptic input device developed for 3D position control. A novel eye-in-hand active visual servoing system is also proposed for the robot to resist unexpected perturbations automatically and deliver surgical tools actively in constrained environments. Finally, a hybrid control strategy combining teleoperation and visual servoing is investigated. Various experiments are conducted to evaluate the performance of the continuum tubular robot and the feasibility and effectiveness of the proposed tele-operation and visual servoing control modes in transnasal surgeries.

Related Publications

1. Liao Wu, Keyu Wu, Li Ting Lynette Teo, and Hongliang Ren, “Tele-Operation and Active Visual Servoing of a Compact Portable Continuum Tubular Robot in Constrained Environments”, Mechatronics, IEEE/ASME Transactions on (submitted)
2. Keyu Wu, Liao Wu and Hongliang Ren, “An Image Based Targeting Method to Guide a Tentacle-like Curvilinear Concentric Tube Robot”, ROBIO 2014, IEEE International Conference on Robotics and Biomimetics, 2014.

People involved

Staff: Liao Wu
Student: Keyu Wu
PI: Hongliang Ren

Deprecated videos FYI only

– tele-operation, visual servoing and hybrid control

– Eye-to-hand Visual Servoing

– Eye-in-hand Visual Servoing in free space

–Tele-operation of the compact tubular robot

– Eye-in-hand Visual Servoing inside a skull model

Simultaneous Hand-Eye, Tool-Flange and Robot-Robot Calibration for Co-manipulators by Solving AXB=YCZ Problem

Abstract

Multi-robot co-manipulation shows great potential to address the limitations of using single robot in complicated tasks such as robotic surgeries. However, the dynamic setup poses great uncertainties in the circumstances of robotic mobility and unstructured environment. Therefore, the relationships among all the base frames (robot-robot calibration) and the relationships between the end-effectors and the other devices such as cameras (hand-eye calibration) and tools (tool-flange calibration) have to be determined constantly in order to enable robotic cooperation in the constantly changing environment. We formulated the problem of hand-eye, tool-flange and robot-robot calibration to a matrix equation AXB=YCZ. A series of generic geometric properties and lemmas were presented, leading to the derivation of the final simultaneous algorithm. In addition to the accurate iterative solution, a closed-form solution was also introduced based on quaternions to give an initial value. To show the feasibility and superiority of the simultaneous method, two non-simultaneous methods were also proposed for comparison. Furthermore, thorough simulations under different noise levels and various robot movements were carried out for both simultaneous and non-simultaneous methods. Experiments on real robots were also performed to evaluate the proposed simultaneous method. The comparison results from both simulations and experiments demonstrated the superior accuracy and efficiency of the simultaneous method.

Problem Formulation

Measurement Data:
Homogeneous transformations from the robot bases to end-effector (A and C), and from tracker to marker (B).
Unknowns:
Homogeneous transformations from one robot base frame to another (Y), and from eye/tool to robot hand/flange (X and Z).
The measurable data A, B and C, and the unknowns X, Y and Z form a transformation loop which can be formulated as, AXB=YCZ (1).
problem

Fig. 1: The relevance and differences among the problem defined in this paper and the other two classical problems in robotics. Our problem formulation can be considered as a superset of the other two.

Approaches

Non-simultaneous Methods

3-Step Method
In the non-simultaneous 3-Step method, the X and Z in (1) are separately calculated as two hand-eye/tool-flange calibrations which can be represented as an AX = XB problem in the first and second steps. This results in two data acquisition procedures, in which the two manipulators carry out at least two rotations whose rotational axes are not parallel or anti-parallel by turns while the other one being kept immobile. The last unknown robot-robot relationship Y could be solved directly using the previously retrieved data by the method of least squares.
2-Step Method
The non-simultaneous 2-Step method formulates the original calibration problem in successive processes which solve AX = XB firstly, and then the AX = YB. The data acquisition procedures and obtained data are the same with the 3-Step method. In contrast to solving robot-robot relationship independently, the 2-Step method solves tool-flange/hand-eye and robot-robot transforms in an AX = YB manner in the second step. This is possible because equation AXB = YCZ can be expressed as (AXB)inv(Z) = YC, which is in an AX = YB form with the solution of X known.

Simultaneous Method

Non-simultaneous methods face a problem of error accumulation, since in these methods the latter steps use the previous solutions as input. As a result, the inaccuracy produced in the former steps will accumulate to the subsequent steps. In addition to accuracy, it is preferred that the two robots participating the calibration procedure simultaneously, which will significantly save the total time required.
In regards to this, a simultaneous method is proposed to improve the accuracy and efficiency of the calibration by solving the original AXB = YCZ problem directly. During the data acquisition procedure, the manipulators simultaneously move to different configurations and the corresponding data set A, B and C are recorded. Then the unknown X, Y and Z are solved simultaneously.

Evaluations

Simulations

To illustrate the feasibility of the proposed methods, intensive simulations have been carried out under different noise situations and by using different numbers of data sets.
simulation

Fig. 2: A schematic diagram which shows the experiment setup consisting of two Puma 560 manipulators, a tracking sensor and a target marker to solve the hand-eye, tool-flange and robot-robot calibration problem.

Simulations Results

For the rotational part, the three methods perform evenly in the accuracy of Z. However, the simultaneous method slightly outperforms in the accuracy of X and significantly in the accuracy of Y than the other two non-simultaneous methods. The results of the translational part are similar to the rotational ones. For the solution of Z, the accuracy of the simultaneous method is as good as the 3-Step method but slightly worse than the 2-Step method. However, the simultaneous method achieves a significantly improvement in the accuracy of X and Y compared to the other two methods.
 
simulation1
simulation2
simulation3

Experiments Results

Besides the simulation, ample real experiments have been conceived and carried out under different configurations to evaluate the proposed methods. As shown in Fig. 6, the experiments involved a Staubli TX60 robot (6 DOFs, averaged repeatability 0.02mm), a Barrett WAM robot (4 DOFs, averaged repeatability 0.05mm) and a NDI Polaris optical tracker (RMS repeatability 0.10mm). The optical tracker was mounted to the last link of the Staubli robot, referred to as sensor robot. The corresponding reflective marker was mounted to the last link of the WAM robot, referred to as marker robot.
experiment

Fig. 6: The experiment is carried out by using a Staubli TX60 robot and a Barrett WAM robot. A NDI Polaris optical tracker is mounted to the Staubli robot to track a reflective marker (invisible from current camera angle) that is mounted to the WAM robot.

To demonstrate the superiority of the simultaneous method in the real experimental scenarios, a 5-fold cross-validation approach is implemented for 200 times for all the calibration methods under all system configurations. For simultaneous method, after data alignment and RANSAC processing, 80% of the remaining data are randomly selected to calculate unknown X, Y, and Z, and 20% are used as test data to evaluate the performance. For 2-Step and 3Step methods, after calculating the unknowns by each method, same test data from the simultaneous method are used to evaluate their performances.

In Fig. 7, the evaluated errors of 200 times 5-fold cross-validation for three proposed methods at three ranges are shown as box plots. Left-tail paired-samples t-tests have been carried out to compare the performances of simultaneous method versus 2-Step and 3-Step methods, respectively. The results indicate that the rotational and translational errors from the simultaneous method are very significantly smaller than the 2-Step and 3-Step methods. Only two non-significant results exist in the rotational performances at medium and far ranges when comparing the simultaneous method with the 3-Step one. Nevertheless, the simultaneous method outperforms the non-simultaneous ones for translation error at all ranges.

experiment1

Fig. 7: Results of 200 times 5-fold cross-validation and left-tail paired-samples t-test at the near, medium and far ranges. The box plots show the rotational and translational error distributions for three methods at three ranges. **, * and N.S. stands for very significant at 99% confidence level, significant and non-significant at 95% confidence level.

Related Publications

1. Liao Wu, Jiaole Wang, Max Q.-H. Meng, and Hongliang Ren, imultaneous Hand-Eye, Tool-Flange and Robot-Robot Calibration for Multi-robot Co-manipulation by Solving AXB = YCZ Problem, Robotics, IEEE Transactions on (Conditionally accepted)
2. Jiaole Wang, Liao Wu and Hongliang Ren, Towards simultaneous coordinate calibrations for cooperative multiple robots, Intelligent Robots and Systems (IROS 2014), 2014 IEEE/RSJ International Conference on. IEEE, 2014: 410-415.

Institute & People Involved

The Chinese University of Hong Kong (CUHK): Jiaole Wang, Student Member, IEEE; Max Q.-H. Meng, Fellow, IEEE
National University of Singapore (NUS): Liao Wu; Hongliang Ren, Member, IEEE

Videos

-Calibration Experiments
 

FlexiDiamond

This is a local copy of the website: http://flexidiamond.blogspot.sg/
diamondlogo

Home-Based Self-Administered Nasopharynscopy

Nasopharynscope is a valuable tool in diagnosing Nasopharyngeal carcinoma in patients since 84% of patients display ulcerations.

Aim: To provide a home-based, affordable and easy-to-use diagnosing kit for detecting Nasopharyngeal Carcinoma

Key features of 5th Generation

  • Clear viewing with a specially designed camera lens
  • Secure extension and contraction lock
  • Tight fit between nylon strings to ensure good power transmission 
  • Diamond cuts to enhance bending capabilities
  • Optical zoom of up to 5 mm due to shooting mechanism

Bending Capability: >90 degrees

Extension and contraction to evade obstacles

Overall Demonstration of Bending and Zooming capability

Specifications

  • Outer Diameter: 7 mm
  • Length of extension portion:25 mm
  • Length of bending segment: 25mm
  • Minimum inserted length: 11-15 cm
  • Gear box: 30 by 20 by 30mm
  • Bending angle: 90 degrees bend per side
  • Distal tip mechanism: Optical zoom
  • Material: Polyurethane (Biocompatible)
  • Stent design: Flexibility
  • Flexible guiding tube

Technical Advantages

  • Large bending angle
  • Extending the camera using the spring mechanism to obtain better optical viewing up to 5mm
  • Endoscope is very flexible with the stent design
  • Able to control the bending of the body segments using cable driven mechanism
  • The bending of the endoscope at the entrance can be controlled flexibly by the guiding shaft

The TEAM

20141103_144553
From Left: Mr Teo Jing Chun, Dr Ren Hongliang, Mr Un Weiyang, Miss Soh Yan Bing, Mr Ong Jun Hao Edmund
Foreground: Mr Yeow Bok Seng

Tendon-driven Flexible Manipulator

Project goals

This project aims to develop a flexible manipulator for transnasal/transoral surgery. Compared with existing surgical manipulators, the developed one should have better performance in workspace and dexterity, thus better facilitate the surgical operation.

Approaches

A constrained tendon-driven serpentine manipulator (CTSM) is designed as shown in Figure 1. It includes an underactuated tendon-driven flexible section, a constraint and a set of tendons. The tendon-driven flexible section is similar to our previous wire-driven robot arm design. It comprises of several identical vertebras, and an elastic tube. Two successive vertebras form a joint and the joint rotation follows the elastic tube bending. Four tendons pass through all the vertebras. For each tendon, the two ends are attached to the distal vertebra and the motor respectively. These tendons are grouped to two pairs and are orthogonally arranged as shown in Figure. 1 (b). One tendon pair controls the bending about X axis and the other tendon pair controls the bending about Y axis. The manipulator bending is planar. The bending angle and bending direction are controlled by the motion of the four tendons. The constraint can be an elastic tube or rigid tube. The constraint translates along the tendon-driven flexible section. Vertebras in the range of the constraint are confined and vertebras out of the range of the constraint are free of rotation. Thus, the last constrained vertebra serves the base of the bending section.
Fig1CTSMDesign

Figure 1 3D design of the CTSM: (a) the assembled and explosion view of the CTSM; (b) the tendon configuration; (c) the cross section view of the joint.

The bending motion of the manipulator is shown in Figure 2: when the insertion of the constraint is 0, the CTSM bends by the tendons as a traditional TSM. By pushing the constraint forward the backbone is segmented to two parts: the proximal constrained section and the distal free bending section. Compared to the distal free bending section, the proximal constrained section is stiffer and the joints’ rotations are smaller. By pushing and pulling the constraint, the lengths of the two sections are controlled.
Fig2CTSMBendingMotion

Fig. 2 Bending motion illustration: (a) the bending section is not constrained; (b) part of the bending section is constrained; (c) the whole bending section is constrained.

Prototype

A prototype is built as shown in Figure 3. In the prototype, the flexible backbone has 27 vertebras. The vertebras are fabricated by 3D printing, and the material used is plastic. Each joint can rotate up to 7.25°.The total length of the flexible backbone is 104mm, and the diameter is 7.5mm. A silicon rubber tube serves the elastic tube. The outer diameter is 3 mm and inner diameter is 2 mm. Four steel wires with nylon coating are used to control the backbone bending. The diameter of the steel is 0.3 mm. The wires are arranged orthogonally, with opponent wires make a pair. Each wire pair is connected to a drum wheel. The rotation of the drum wheel is controlled by a servo motor. The diameter of the drum wheel is 50 mm. The wires are guided by a Teflon tube, whose outer diameter is 0.9 mm and inner diameter is 0.5 mm. The replaceable constraint is hold by a chuck, which is mounted on the linear actuator. The range of the linear actuator is 100 mm.

Results

By changing the stiffness ratio between the flexible bending section and the overall stiffness λ, the workspace of the CTSM is as shown in Figure 4. In the simulation the length of the CTSM is 100 mm, and the number of vertebrae is 25.
Fig4workspace

Fig. 4 workspace comparison: (a) traditional TSM; (b) CTSM with elastic constraint; (c) CTSM with elastic constraint; (d) CTSM with rigid constraint.

When the CTSM with a rigid constraint is attached to a mobile base, the workspace and dexterity distribution are shown in Figure 5. For the tendon-driven serpentine manipulator (TSM), the dexterity is indexed as the kinematic flexibility. For a traditional TSM, the kinematic flexibility is 1 in most places; the maximum is 2. For the designed CTSM, the kinematic flexibility is enhances all over the workspace and the maximum is 15.
 

Fig5Comparison-wkdb15

Figure 5 Comparison of the dexterity distribution over the workspace: (a) traditional TSM; (b) CTSM with λ=0.

People involved

Staff: Zheng Li
Visiting Students: Gui Fu, Zhengchu Tan, Jan Feiling
PIs: Hongliang Ren and Haoyong Yu

Experiment Videos

– Phantom tests

– CTSM Experiments in ex-vivo hearts and phantoms (2014/11/22)

Publications

1. Zheng Li, Haoyong Yu and Hongliang Ren, “A Novel Constrained Tendon-driven Serpentine Manipulator (CTSM)”, ICRA 2015 (under review)
2. Zheng Li, Haoyong Yu and Hongliang Ren, “A Novel Underactuated Wire-driven Flexible Robotic Arm with Controllable Bending Section Length”, ICRA 2014 Workshop on Advances in Flexible Robots for Surgical Interventions, Hong Kong, May 31-June 7, 2014
3. Zheng Li, Ruxu Du, Haoyong Yu and Hongliang Ren, “Statics Modeling of an Underactuated Wire-driven Flexible Robotic Arm”,IEEE BioRob 2014, Sao Pauo, Brazil, Aug12-15, 2014

Presentation at BIOROB2014

Presentation at ICRA 2014

Poster at ICRA 2014

<!–
Fig3CTSMprototype

Fig. 3 CTSM prototype.

.–>

Tip Tracking and Shape Sensing for Flexible Surgical Robots

Project Goals

As a typical minimally invasive surgery, transoral surgery brings to patients significant benefits such as decreased intra-operative blood loss, less post-operative complication morbidity, shorter hospitalization length and recovery period. Flexible surgical robot (such as tendon/wire/cable-driven robot and concentric tube robot) is an efficient device for transoral inspection and diagnosis. It can work well in complicated and confined environments. One drawback of this method is that the real time tip position and shape information cannot be well estimated, especially when there is payload on the end effector. To address these challenges, we focus on a novel tip tracking and shape sensing method for the flexible surgical robot.

Approaches

The proposed method is based on the positional and directional information of limited specific joints of the robot, which are estimated with an electromagnetic tracking system. Electromagnetic sensors have been mounted in the tip of the robot to provide the tip position and direction information. Based on the section number of the robot, some other sensors will be mounted in the specific position of the robot to realize the shape sensing. The shape sensing method is based on multi quadratic Bézier curves.
Fig1electromagnetic

Fig.1 Electromagnetic tracking method.

The electromagnetic tracking method is shown in Fig.1. A uniaxial sensing coil is used as the target and sensing the magnetic field that generated by the six transmitting coils. These six coils are stimulated sequentially. The position and orientation information of the sensing coil can then be estimated based on the sensing signals.
Fig2shapesensing

Fig.2 Shape sensing method.

Fig.2 shows the shape sensing method for multi-section flexible by using multi quadratic Bézier curves. For a N sections robot, ⌈N/2⌉ electromagnetic sensors will be mounted in the tail of the (N-2k)th section, where 0≤k<n/2. Therefore, by utilizing the positional and directional information of the sensors, each section can be reconstructed based on a quadratic Bezier curve. Compared to the image based method, this method is easy to setup; compared to the FBG based method, curvature information is not used and fewer sensors are needed in the proposed method.

Results and Remarks

Fig3twouniaxial

Fig.3 Two Uniaxial electromagnetic sensing coils are mounted in both ends of the device.

We have applied the method on a 10-joints wire-driven flexible robot. As shown in Fig.3, two uniaxial electromagnetic sensors (Aurora Shielded and Isolated 5DOF Sensor, 0.9* 12mm) have been mounted on both ends of the robot. Fig.4 shows the average errors of the experimental results of each S shape curve reconstruction in the experiments. The whole average error is 1.4mm.
We have also applied the method on a two-section concentric tube. As shown in Fig.5, a uniaxial sensor has been mounted in the tip of the robot. The tracking results can be seen in the video.
Fig4wiredriven

Fig.4 Experimental results for the wire-driven flexible robot.

Fig5tiptracking

Fig.5 Tip tracking and shape sensing for concentric tube robot. The result can be seen in the video below.

The primary contributions of our work are summarized as follows:
1)A shape sensing method based on Bézier curve fitting and electromagnetic tracking is proposed. This method needs only the positional and directional information of some specific position of the curved robot.
2)Only limited sensors are needed, and thus very few modifications are required on the robot.
3)Compared with other methods, the proposed method is easy to set up and has a good accuracy.

People Involved

Staff: Shuang Song, Zheng Li
Investigators: Hongliang Ren, Haoyong Yu

Video

Publications

[1] Shuang Song, Wan Qiao, Baopu Li, Chao Hu, Hongliang Ren and Max Meng. “An Efficient Magnetic Tracking Method Using Uniaxial Sensing Coil”. Magnetics, IEEE Transactions on, 2014. 50(1), Article#: 4003707
[2] Shuang Song, Hongliang Ren and Haoyong Yu. “An Improved Magnetic Tracking Method using Rotating Uniaxial Coil with Sparse Points and Closed Form Analytic Solution”. IEEE Sensors Journal, 14(10): 3585-3592, 2014
[3] Shuang Song, Baopu Li, Wan Qiao, Chao Hu, Hongliang Ren, Haoyong Yu, Qi Zhang, Max Q.-H. Meng and Guoqing Xu. “6-D Magnetic Localization and Orientation Method for an Annular Magnet Based on a Closed-Form Analytical Model”. IEEE Transactions on Magnetics. 2014, 50(9), Article#: 5000411

ETH Image Based Visual Servoing to Guide Flexible Robots

Video Demo

Eye-To-Hand Image Based Visual Servoing to Guide Flexible Robots

Project goals

Flexible robots including active cannula or cable driven continuum robots are typically suitable for such minimally invasive surgeries because they are able to present various flexible shapes with great dexterity, which strengthens the ability of collision avoidance and enlarges the reachability of operation tools. Using model based control method will lead to artificial singularities and even inverted mapping in many situations because the models are usually developed in free space and cannot perform effectively in constrained environments. Therefore, the goal of this project is control the motion of a tentacle-like curvilinear concentric tube robot by model-less visual servoing.

Approaches

A two-dimensional planar manipulator is constructed by enabling only the three translation inputs of a six DOF concentric tube robot. As shown in Fig. 1, the concentric tube manipulator is controlled using a PID controller and the images captured by an uncalibrated camera are used as visual feedback.
Fig1setup

Fig. 1. The experimental setup includes a concentric tube robot, a camera, a laptop, a marker and a target.

The visual tracking of the concentric tube robot is based on shape detection. The circular marker is attached to the tip of the concentric tube robot and a square target is given for the tip to trace. During the experiments, the coordinates of the marker centroid and target centroid are calculated while the next target position is calculated at the same time as shown in Fig. 2.
Fig2workingmechanism

Fig. 2. Working mechanism of the system. Top: translations of the three tubes. Bottom: marker, final target and the next target position on the image plane.

Fig3overview

Fig. 3. Overview of the control algorithm. The Jacobian matrix is estimated based on the measurements of each incremental movement detected from the camera.

The framework of the controlling the robot is shown in Fig. 3. The initial Jacobian matrix is acquired by running each individual motor separately and measuring the change of tip position of the robot in the image space. Then the optimal control is achieved by solving a typical redundant inverse kinematics. And finally the Jacobian matrix is continuously estimated based on the measured displacements.

Results

To evaluate the proposed model-less algorithm, a simulation was carried out on MATLAB first. The desired and actual trajectory was shown in Fig. 4, from which it could be seen that the robot succeeded in following the reference trajectory and reaching the target position.
Fig4simulationcrt

Fig. 4. Simulation of using the proposed algorithm to control a concentric tube robot.

The proposed algorithm was also implemented on a physical concentric tube robot in free space. It was found the robot was able to reach goal with zero steady state error in all trials as shown in Fig. 5.
Fig5experiments

Fig. 5. The concentric tube robot is able to reach a desired goal using the proposed method. Top: the motion of the robot. Bottom: the reference and actual trajectories of two experiments.

People involved

Staff: Keyu WU, Liao WU
PI: Hongliang REN

Publications

1. Keyu Wu, Liao Wu and Hongliang Ren, “An Image Based Targeting Method to Guide a Tentacle-like Curvilinear Concentric Tube Robot”, ROBIO 2014, IEEE International Conference on Robotics and Biomimetics, 2014.

Nasopharyngeal Carcinoma Surveillance

Project Goals:

Nasopharyngeal carcinoma (NPC) is a tumor arising from the epithelial cells that cover the surface and line the nasopharynx. The concern about NPC in our studies is that it is more common in regions in East Asia and Africa, specifically Southeast Asia. Due to the high tendency for NPC to develop into metastatic dissemination, about 30- 60% of locally advanced patients will develop distant metastasis and die of disseminated disease. Thus this implies that apart from early diagnosis, it is also of paramount importance to locally monitor for the recurrence of NPC or the development of distant metastasis. Therefore, there is a need for a patient-operated, in-vivo surveillance system.

Approaches:

The approach for this project is that it has to be a remote surveillance system that is able to monitor the growth of the tumor in the nasopharyngeal region independently by the patient. The design requirements are as follows below:
1. The device must be made of medically approved materials that are mechanically strong enough to withstand 1 to 2 years of constant use. This is because the average time period for NPC surveillance spans to around 2 years.
2. The device must be durable so as to last the entire time period of use.
3. The device must house a camera module, which is rotatable to the minimum of 90 degrees, such that it can accurately pan throughout the entire nasopharynx region.
Additional aims were also realized in the device design as follows:
1. The device must be made in an economically feasible manner, such that it is able to reduce medical costs as much as possible.
2. The device outcome must be similar to any other method of NPC surveillance so that the quality of the monitoring system is not compromised.
3. The device must be patient-administered, meaning that the patient is able to deploy and use the device without the assistance of medical personnel. This is so as to decrease patient dependence on the healthcare system and also an attempt to decrease the burden on clinicians.
4. The device must be as safe and hassle-free to the patient as possible.

Results and Remarks

The first prototypical device comprises of the following components:
1. Camera Module
2. Arm Head and Hook
3. Arm
4. Wheel and Cover
5. Handle
The camera module houses a mini-camera, which will be able to obtain imaging output from within the nasopharyngeal region after its deployment into the nasal cavity. This housing contains two axles on either side, to enable the rotational mechanism. The camera module is then attached to the arm head, which clicks the axle of the camera into place.
The arm head also contains a hook, whose purpose is to ensure the stability of the device once deployed to the site of the vomer bone. The hook will allow the easy positioning of the camera module to the site and also increase the stability of the device during image capture. This decreases the possibilities of blurred imaging outputs.
The rotational mechanism is mainly powered by three components: (i) the camera module and axle, (ii) the arm, and (iii) the wheel. A thin piece of nylon wire is first threaded through the camera module, then threaded down the tunnels in the arm and finally around the wheel. The rotation mechanism works when the wheel is turned in either direction.
The results of the design verification experiments show that the maximum force required to fracture the Veroclear tip and head are 5.1N and 15.6N respectively. The maximum tensile strength of nylon is 262.4 MPa. The arm can bend to a maximum of 7.3 cm with a force of 15.3N before fracture. FEA shows that even under an exaggerated maximum loading of 100N, the device does not fracture.
The device is able to capture images from within the nasopharyngeal region from the mini camera. This was done by inserting the device through the nasal passageway of a phantom skull and the tumor is shown by the piece of BluTack.
The forces obtained for fracture and/or bending of the Veroclear arm are well beyond the acceptable range of forces as set by the acceptance criteria. This shows that the Veroclear arm passes the first stage of verification testing to determine is safety and suitability in this design. However, to add further to the safety of the device, it is aimed that the final device will be made of a much more mechanically strong material, which is also medically approved: 316L Stainless Steel. From the extrapolated calculations and research of 316L Stainless Steel through FEA, it can be concluded that 316L Stainless Steel is also a good, if not better choice of material for the manufacturing of this device due to its excellent mechanical strength and durability.
Video to be uploaded

People Involved

Undergraduate Students: Neerajha Ram, Khor Jing An, Paul Ng, Ong Jun Shu, Anselina Goh
Advisor: Dr. Hongliang Ren

Awards

Awarded the MOST ELEGANT DESIGN INSTRUMENTATION AWARD at the BN3101 Presentations 2013.

Surgical Tracking Based on Stereo Vision and Depth Sensing

Project Goals:

The objective of this research is to incorporate multiple sensors at broad spectrum, including stereo infrared (IR) cameras, color (or RGB) cameras and depth sensors to perceive the surgical environment. Features extracted from each modality can contribute to the cognition of complex surgical environment or procedures. Additionally, their combination can provide higher robustness and accuracy beyond what is obtained from single sensing modality. As a preliminary study, we propose a multi-sensor fusion approach for localizing surgical instruments. We developed an integrated dual Kinect tracking system to validate the proposed hierarchical tracking approach.

Approaches:

This project considers the problem of improving the surgical instrument tracking accuracy by multi-sensor fusion technique in computer vision. We proposed a hierarchical fusion algorithm for integrating the tracking results from depth sensor, IR camera pair and RGB camera pair. Fig. 1 summarized the algorithm involved in this project. It can be divided into the “low-level” and the “high-level” fusion.

Fig. 1 Block diagram of hierarchical fusion algorithm.


The low-level fusion is to improve the speed and robustness of marker feature extraction before triangulating the tool tip position in IR and RGB camera pair. The IR and RGB camera are modeled as pin-hole cameras.  The depth data of the tool can be used as a priori for marker detection. The working area of the tracking tool is supposed to be limited in a reasonable volume v(x, y, z) that can be used to refine the search area for feature extraction, which could reduce the computational cost for real-time applications.
The high-level fusion is to reach a highly accurate tracking result by fusing two measurements. We employ the covariance intersection (CI) algorithm to estimate a new tracking result with less covariance.

Experiments

To demonstrate the proposed algorithm, we designed a hybrid marker-based tracking tool (Fig. 2) that incorporates the cross-based feature in visible modality and retro-reflective marker based feature in infra-red modality to get a fused tracking of the customized tool tip. To evaluate the performance of the proposed method, we employ two Kinects to build the experimental setup. Fig. 3 shows the prototype of multi-sensor fusion tracker for the experiment, which indicates that the CI-based fusion approaches obviously tend to be better than the separate IR tracker or RGB tracker.  The mean error and deviation of the fusion algorithm are all improved.
Hybrid marker

Fig. 3 Dual Kinect tracking system

People Involved

Staffs: Wei LIU, Shuang SONG, Andy Lim
Advisor: Dr. Hongliang Ren
Collaborator: Wei ZHANG

Publications

[1] Ren, H.; LIU, W. & LIM, A. Marker-Based Instrument Tracking Using Dual Kinect Sensors for Navigated Surgery IEEE Transactions on Automation Science and Engineering, 2013
[2] Liu, W.; Ren, H.; Zhang, W. & Song, S. Cognitive Tracking of Surgical Instruments Based on Stereo Vision and Depth Sensing, ROBIO 2013, IEEE International Conference on Robotics and Biomimetics, 2013

Related FYP Project

Andy Lim: Marker-Based Surgical Tracking With Multiple Modalities Using Microsoft Kinect

References

[1] H. Ren, D. Rank, M. Merdes, J. Stallkamp, and P. Kazanzides, “Multi-sensor data fusion in an integrated tracking system for endoscopic surgery,” IEEE Transactions on Information Technology in Biomedicine, vol. 16, no. 1, pp. 106 – 111, 2012.
[2] W. Liu, C. Hu, Q. He, and M.-H. Meng, “A three-dimensional visual localization system based on four inexpensive video cameras,” in Information and Automation (ICIA), 2010 IEEE International Conference on. IEEE, 2010, pp. 1065–1070.
[3] F. Faion, S. Friedberger, A. Zea, and U. D. Hanebeck, “Intelligent sensor-scheduling for multi-kinect-tracking,” in Intelligent Robots and Systems (IROS), 2012 IEEE/RSJ International Conference on. IEEE, 2012, pp. 3993–3999.

FYP: Surgical Tracking With Multiple Microsoft Kinects

FYP Project Goals

The aim of this project is to perform tracking of surgical instruments utilizing the Kinect sensors. With the advances in computing and imaging technologies in the recent years, visual limitations during surgery such as those due to poor depth perception and limited field of view, can be overcome by using computer-assisted systems. 3D models of the patient’s anatomy (obtained during pre-operative planning via Computed Tomography scans or Magnetic Resonance Imaging) can be combined with intraoperative information such as the 3D pose and orientation of surgical instruments. Such a computer-assisted system will reduce surgical mistakes and help identify unnecessary or imperfect surgical movements, effectively increasing the success rate of the surgeries.
For computer-assisted systems to work, accurate spatial information of surgical instruments is required. Most surgical tools are capable of 6 degrees of freedom (6DoF) movement, which includes the translation in the x, y, z- axes as well as the rotation about these axes. The introduction of Microsoft Kinect sensor raises the possibility of an alternative optical tracking system for surgical instruments.
This project’s objective would be the development of an optical tracking system for surgical instruments utilising the capabilities of the Kinect sensor. In this part of the project, the focus will be on marker-based tracking using the Kinect sensor.

Approach

  • The setup for the tracking of surgical instruments consists of two Kinects placed side by side with overlapping field of views.
  • The calibration board used to find out the intrinsic camera parameters as well as the relative position of the cameras. This allows us to calculate the fundamental matrix, which is essential for epipolar geometry calculations used in 3D point reconstruction. (a) without external LED illumination (b) with LED illumination. The same board is used for RGB camera calibration.
  • Seeded region growing allows the segmentation of retro-reflective markers from the duller background. The algorithm is implemented through OpenCV.
  • Corner detection algorithm: the cornerSubPix algorithm from OpenCV is used to refine the position of the corners. This results in sub-pixel accuracy of the corner position.

Current Results

  • The RMS error for IRR and checkerboard tracking ranges from 0.37 to 0.68 mm and 0.18 to 0.37 mm respectively over a range of 1.2 m. Checkerboard tracking is found to be more accurate. Error increases with distance from camera.
  • The jitter for the checkerboard tracking system was investigated and it was found to range from 0.071 mm to 0.29 mm over the range of 1.2 m.
  • (dots) Measurement of jitter plotted against the distance from the left camera. (line) the data is fitted to a polynomial of order 2 to analyze how jitter varies with depth.

 

People Involved

FYP Student: Andy Lim Yong Mong
Research Engineer: Liu Wei
Advisor: Dr. Ren Hongliang

Related Project

Surgical Tracking Based on Stereo Vision and Depth Sensing

References

[1] Sun, W., Yang, X., Xiao, S., & Hu, W. (2008). Robust Checkerboard Recognition for Efficient Nonplanar Geometry Registration in Projector-camera Systems. Proceedings of the 5th ACM/IEEE International Workshop on Projector camera systems. ACM.
[2] R. Hartley and A. Zisserman, Multiple View Geometry in Computer Vision, 2 ed., Cambridge: Cambridge University Press, 2003.
[3] Q. He, C. Hu, W. Liu, N. Wei, M. Q.-H. Meng, L. Liu and C. Wang, “Simple 3-D Point Reconstruction Methods With Accuracy Prediction for Multiocular System, “IEEE/ASME Transactions on Mechatronics, vol. 18, no. 1, pp. 366-375, 2013

Statistical Humerus Implants and Associated Intramedullary Robotics

Project Goals

The sizes of current off-the-shelf humerus implants are unable to accommodate Asian patients since they are mainly produced for American and European populations according to locally collected data. By creating statistical humerus atlases based on Asian data, gender-specific and region-specific humeral implants can be developed by considering the characteristics of the statistical atlas constructed in order to improve stability of the fixation and avoid related complications. Besides, it is envisioned that the statistical atlas can serve as a critical reference for development and evaluation of robots in surgical procedures. Particularly, for the surgical and interventional procedures in the confined and rotated intramedullary space, the curvature and shape statistics of internal humerus canal is of great significance for the dedicatedly design of snake-like curvilinear tubular robot.

In this project, an efficient way has been demonstrated to construct statistical atlas by adopting an efficient alignment algorithm with improved efficiency and good accuracy. The constructed humerus atlas is then regarded as the reference for design of various humerus implants and development of snake-like concentric tube robots.

Approach

Statistical Atlas Construction: A three-step algorithm is adopted in statistical atlas construction, including segmentation, alignment and principal component analysis (PCA). Segmentation is to extract the desired surface mesh information of the humeri from the raw CT data and alignment is to align all the samples. The final step is to perform the principal component analysis of the shapes and represent the statistical model using principal components.

Creation and application of a statistical humerus atlas

Creation and application of a statistical humerus atlas

Centerline Extraction for Intramedullary Robot Design: The Laplacian-Based Contraction Method is adopted to extract the centerline of the humerus atlas. The purpose is to explore the intramedullary structure of the humerus since the curvature and shape statistics of internal humerus canal is significant for the design of snake-like curvilinear tubular robot.

Centerline Extraction Process

Centerline Extraction Process

Curvature Analysis for Design of Humerus Implants: The maximum principal curvature is depicted in the below Figure. The curvature analysis is to study the statistical surface curvature of the humerus atlas, in order to assist the design of humerus implants such as proximal and distal humerus locking plates, both used in orthopaedic trauma fixation.

Principal curvature of the statistical humerus atlas

Principal curvature of the statistical humerus atlas

Current Results

By adopting the novel atlas construction algorithm, the statistical humerus atlas is constructed as shown in the below figure, where the shape variation is along the first three principal components (PCs) and each row is generated by varying the shape with -3 to +3 standard deviations.

The variation along the first principal component is shown here (click to view the animation). From -3std to +3std, the length of the humerus model is increased while the width is decreased.

Shape variation along the 1st principal component

Shape variation along the 1st principal component

Moreover, by analyzing the characteristics of the humerus atlas, the intramedullary continuum robot design and the proximal humerus locking plate are depicted in the following figures.

Design of intramedullary continuum robot based on the statistical humerus atlas

Design of intramedullary continuum robot based on the statistical humerus atlas

Proximal humerus locking plate

Proximal humerus locking plate

People Involved

Staff: Keyu WU
Advisor: Hongliang REN
Clinicians: Keng Lin Wong, Zubin Jimmy Daruwalla, Diarmuid Murphy, National University Hospital

Publications

  • Wu K, Wong FKL, Ng SJK, Quek ST, Zhou B, Murphy D, Daruwalla ZJ and Ren H (2015), “Statistical atlas-based morphological variation analysis of the asian humerus: Towards consistent allometric implant positioning”, International Journal of Computer Assisted Radiology and Surgery. Vol. 10(3), pp. 317-327. Springer Berlin Heidelberg
  • Wu K, Daruwalla ZJ, Wong FKL, Murphyand D and Ren H (2015), “Development and Selection of Asian-specific Humeral Implants based on Statistical Atlas: Towards Planning Minimally Invasive Surgery”, International Journal of Computer Assisted Radiology and Surgery. Vol. 10(8), pp. 1333-1345. Springer Berlin Heidelberg.
  • Wu, K.; Wong, F. K. L.; Daruwalla, Z. J.; Murphy, D. & Ren, H. Statistical Humerus Atlas for Optimal Design of Asian-Specific Humerus Implants and Associated Intramedullary Robotics, ROBIO 2013, IEEE International Conference on Robotics and Biomimetics, 2013; (Best Paper Finalist award)

Supporting materials

Supplementary information for

Statistical Atlas Based Morphologic Variation Analysis of the Asian Humerus: Towards Consistent Allometric Implant Positioning

K. Wu, K. L. Wong, S. J. K. Ng, S. T. Quek, B. Zhou, D. P. Murphy, Z. J. Daruwalla, H. Ren*

 

All data are published in .nii format, which can be opened by ITK-SNAP (http://www.itksnap.org/pmwiki/pmwiki.php) and 3D Slicer (http://www.slicer.org/).

Table 1. Information of the subjects.

Study Number

Male/Female

Age

Race

Weight (kg)

Height (cm)

Exercise habit:

S = sedentary,

A = active

Left/Right:

L = left,

R = right

5260823

F

61

C

67.9

143

S

L

5190438

M

16

C

55.6

160

A

R

5186672

M

63

C

67.5

160

A

L

5172526

M

50

C

61.0

170

S

L

5018737

F

77

C

57.9

151

S

R

4636229

M

54

C

42.8

161

S

L

4585165

M

38

C

60.3

171

A

L & R

4481609

F

83

C

60.1

149

S

L

4448930

F

49

I

73.7

150

S

R

4320030

M

69

C

63.7

163

S

L

4111802

M

63

C

57.4

160

S

L

3969853

F

61

C

64.3

157

A

R

3564131

M

19

C

97.5

167

A

L

3495415

M

74

M

57.1

175

S

L

3827904

M

33

M

64.2

170

A

L

3722692

F

73

I

57.3

151

S

L

3768879

M

20

C

65.0

170

A

L

3771777

F

74

C

53.3

165

S

L & R

3159961

M

51

C

60.0

170

A

L

3273883

F

80

C

54.8

155

S

L

3384844

F

71

C

53.1

155

S

R

3353378

F

78

M

40.0

140

S

L

3271006

F

59

M

60.0

151

S

L

3189139

M

47

C

72.0

179

A

R

3132590

M

22

M

79.0

168

A

L

3143094

M

23

C

60.6

162

A

R

3282457

F

90

C

41.2

150

S

L

3296805

M

57

M

61.2

160

S

L

3326396

M

21

C

76.0

175

A

L

3338591

F

61

C

56.0

153

S

L & R

3060290

M

21

M

73.0

160

A

L

5581085

F

49

M

81.9

159

S

L & R

5691045

F

45

C

45.1

161

A

L

5731852

F

87

C

58.2

150

S

R

5733267

F

57

C

56.4

142

S

L & R

5622431

M

64

I

52.9

162

A

R

6007641

M

44

I

74.2

165

A

L

6013682

F

74

C

52.0

153

S

R

5504982

F

24

C

54.0

153

A

L

image001L
Fig. 1. Statistical male humerus atlas (left). The shape variation is along the first three principal components (PCs) and each row is generated by varying the shape with standard deviations ranging from -3√(λ_k ) to +3√(λ_k ).

image004R
Fig. 2. Statistical female humerus atlas (left). The shape variation is along the first three principal components (PCs) and each row is generated by varying the shape with standard deviations ranging from -3√(λ_k ) to +3√(λ_k ).

References

[1] H. Ren, N. V. Vasilyev, and P. E. Dupont, “Detection of curved robots using 3d ultrasound,” in Intelligent Robots and Systems (IROS), 2011 IEEE/RSJ International Conference on. IEEE, 2011, pp. 2083–2089.
[2] H. Ren and P. E. Dupont, “Artifacts reduction and tubular structure enhancement in 3d ultrasound images,” in International Conference of the IEEE Engineering in Medicine and Biology Society, EMBC, 2011.
[3] G. Chintalapani, L. M. Ellingsen, O. Sadowsky, J. L. Prince, and R. H. Taylor, “Statistical atlases of bone anatomy: construction, iterative improvement and validation,” in Medical Image Computing and Computer-Assisted Intervention–MICCAI 2007. Springer, 2007, pp. 499–506.
[4] H. Ren and P. E. Dupont, “Tubular enhanced geodesic active contours for continuum robot detection using 3d ultrasound,” in IEEE International Conference on Robotics and Automation, ICRA ’12, 2012.
[5] X. Kang, H. Ren, J. Li, and W.-P. Yau, “Statistical atlas based registration and planning for ablating bone tumors in minimally invasive interventions,” in Robotics and Biomimetics (ROBIO), 2012 IEEE International Conference on. IEEE, 2012, pp. 606–611.
[6] J. Cao, A. Tagliasacchi, M. Olson, H. Zhang, Z. Su, “Point Cloud Skeletons via Laplacian Based Contraction,” in Shape Modeling International Conference (SMI), pp. 21-23, 2010.