System Design of Humanoid Robot DYROS-JETdyros.snu.ac.kr/wp-content/uploads/2019/01/0170.pdf ·...

5
System Design of Humanoid Robot DYROS-JET* Suhan Park 1 , Jaehoon Sim 1 , and Jaeheung Park 1,2 Abstract—To perform various tasks for humans, humanoid robots are designed to comprise multiple joints that provide them with both mobility and manipulability enabled by a kinematic structure similar to that of humans. Herein, we introduce a system design created to control a robot with numerous degrees of freedom. Our communication system is constructed to simultaneously control multiple joints and improve control performance by fully exploiting the control frequency. We also consider the design of the input/output interface for multiple sensors that are essential for stable walking and the manipulation of humanoid robots. A fail-safe algorithm is implemented for the software modules and the controller, and the proposed system design is experimentally verified. I. INTRODUCTION Humanoid robots exhibit promising potential for use in various fields, such as at service and industrial sites, owing to their high mobility and manipulation ability. Therefore, numerous humanoid robots have already been developed [1]– [3]. High-speed communication and a fail-safe controller for multiple devices are required to control them, because humanoid robots have many degrees of freedom. In addition, their limited weight and size cause difficulties in terms of choosing appropriate components. Therefore, various aspects must be considered to design the complete system of a hu- manoid robot. We separate theses aspects into the following three major categories. First, synchronized control of multiple actuators should be implemented. All the joints of the robot must be si- multaneously controlled while performing the desired task. In addition, the control period of the actuators should be constant; otherwise, instability may occur during operation. The control frequency should be fully exploited to provide more precise control of the robot. Second, input/output interfaces for the use of various sen- sors are required. Based on the desired functions, humanoid robots require multiple sensors of different types, such as the force–torque sensor for impedance control [4], the tactile sensor for object manipulation [5], and the external joint encoder [6]. Finally, a modular design and a fail-safe algorithm for the control system are necessary. Despite the interconnected *This work was supported by the National Research Foundation of Korea (NRF) grant funded by the Korea government (MSIP) (No. NRF- 2015R1A2A1A10055798) 1 Suhan Park, Jaehoon Sim, and Jaeheung Park are with Department of Transdisciplinary Studies, Graduate School of Convergence Science and Technology, Seoul National University, Republic of Korea. {psh117, simjeh, park73}@snu.ac.kr 2 Jaeheung Park is also with Advanced Institutes of Convergence Tech- nology(AICT), Republic of Korea. He is the corresponding author of this paper. (a) (b) Fig. 1: (a) Joint configuration of the humanoid robot DYROS-JET; (b) picture of DYROS-JET. complex software structure, modularization can lower the system’s complexity. The robot operating system (ROS) [7] has been recently introduced to facilitate the development of specialized software via the modularization of robotic software. ROS has been promoted in the development of various humanoid robot systems [8]–[10] and we used it to develop our software system. In this study, we introduce the system design of a hu- manoid robot DYROS-JET shown in Fig. 1(b). DYROS- JET was developed for general industrial tasks by upgrading THORMANG by Team SNU, which participated in the 2015 DARPA Robotics Challenge Finals [11], [12]. Herein, Section II presents the detailed design of the DYROS-JET system; Section III explores the verification and application of the system design; and Section IV concludes the paper. II. SYSTEM DESIGN In this section, we introduce the system design used to operate DYROS-JET by describing each component of the hardware structure and the modules of the software structure. Figures 2 and 3 present the robot’s hardware and software structures, respectively. A detailed description of theses structures is included in the following subsection. A. Basic Specification The robot is 1.63 m tall and weighs 50 kg. Each arm has a payload of 1 kg with seven actuators, whereas each leg comprises six actuators. Two actuators are used to rotate the Proceedings of the 2019 IEEE/SICE International Symposium on System Integration Paris, France, January 14-16, 2019 978-1-5386-3615-2/19/$31.00 ©2019 IEEE 746

Transcript of System Design of Humanoid Robot DYROS-JETdyros.snu.ac.kr/wp-content/uploads/2019/01/0170.pdf ·...

Page 1: System Design of Humanoid Robot DYROS-JETdyros.snu.ac.kr/wp-content/uploads/2019/01/0170.pdf · manoid robot. We separate theses aspects into the following three major categories.

System Design of Humanoid Robot DYROS-JET*

Suhan Park1, Jaehoon Sim1, and Jaeheung Park1,2

Abstract— To perform various tasks for humans, humanoidrobots are designed to comprise multiple joints that providethem with both mobility and manipulability enabled by akinematic structure similar to that of humans. Herein, weintroduce a system design created to control a robot withnumerous degrees of freedom. Our communication systemis constructed to simultaneously control multiple joints andimprove control performance by fully exploiting the controlfrequency. We also consider the design of the input/outputinterface for multiple sensors that are essential for stablewalking and the manipulation of humanoid robots. A fail-safealgorithm is implemented for the software modules and thecontroller, and the proposed system design is experimentallyverified.

I. INTRODUCTION

Humanoid robots exhibit promising potential for use invarious fields, such as at service and industrial sites, owingto their high mobility and manipulation ability. Therefore,numerous humanoid robots have already been developed [1]–[3]. High-speed communication and a fail-safe controllerfor multiple devices are required to control them, becausehumanoid robots have many degrees of freedom. In addition,their limited weight and size cause difficulties in terms ofchoosing appropriate components. Therefore, various aspectsmust be considered to design the complete system of a hu-manoid robot. We separate theses aspects into the followingthree major categories.

First, synchronized control of multiple actuators shouldbe implemented. All the joints of the robot must be si-multaneously controlled while performing the desired task.In addition, the control period of the actuators should beconstant; otherwise, instability may occur during operation.The control frequency should be fully exploited to providemore precise control of the robot.

Second, input/output interfaces for the use of various sen-sors are required. Based on the desired functions, humanoidrobots require multiple sensors of different types, such as theforce–torque sensor for impedance control [4], the tactilesensor for object manipulation [5], and the external jointencoder [6].

Finally, a modular design and a fail-safe algorithm forthe control system are necessary. Despite the interconnected

*This work was supported by the National Research Foundation ofKorea (NRF) grant funded by the Korea government (MSIP) (No. NRF-2015R1A2A1A10055798)

1Suhan Park, Jaehoon Sim, and Jaeheung Park are with Department ofTransdisciplinary Studies, Graduate School of Convergence Science andTechnology, Seoul National University, Republic of Korea. {psh117,simjeh, park73}@snu.ac.kr

2Jaeheung Park is also with Advanced Institutes of Convergence Tech-nology(AICT), Republic of Korea. He is the corresponding author of thispaper.

(a) (b)

Fig. 1: (a) Joint configuration of the humanoid robotDYROS-JET; (b) picture of DYROS-JET.

complex software structure, modularization can lower thesystem’s complexity. The robot operating system (ROS) [7]has been recently introduced to facilitate the developmentof specialized software via the modularization of roboticsoftware. ROS has been promoted in the development ofvarious humanoid robot systems [8]–[10] and we used it todevelop our software system.

In this study, we introduce the system design of a hu-manoid robot DYROS-JET shown in Fig. 1(b). DYROS-JET was developed for general industrial tasks by upgradingTHORMANG by Team SNU, which participated in the2015 DARPA Robotics Challenge Finals [11], [12]. Herein,Section II presents the detailed design of the DYROS-JETsystem; Section III explores the verification and applicationof the system design; and Section IV concludes the paper.

II. SYSTEM DESIGN

In this section, we introduce the system design usedto operate DYROS-JET by describing each component ofthe hardware structure and the modules of the softwarestructure. Figures 2 and 3 present the robot’s hardware andsoftware structures, respectively. A detailed description oftheses structures is included in the following subsection.

A. Basic Specification

The robot is 1.63 m tall and weighs 50 kg. Each arm hasa payload of 1 kg with seven actuators, whereas each legcomprises six actuators. Two actuators are used to rotate the

Proceedings of the 2019 IEEE/SICEInternational Symposium on System Integration Paris, France, January 14-16, 2019

978-1-5386-3615-2/19/$31.00 ©2019 IEEE 746

Page 2: System Design of Humanoid Robot DYROS-JETdyros.snu.ac.kr/wp-content/uploads/2019/01/0170.pdf · manoid robot. We separate theses aspects into the following three major categories.

OPERATOR SIDE

ROBOT SIDE

Robot Computer

Unit

Robot Perception

Unit

LIDAR

Left Leg External Encoder

FT Sensors

RS-485 Serial

Comm.

DAQRouter

IMU

ZED Stereo

Camera

Left Arm Motors

Right Arm Motors

Left Leg Motors

Right Leg Motors

RS-

48

5

AnalogPCI-EEthernet

Right Leg External Encoder

Ethern

et

USB 3.0

USB

Sensor/Actuator

Router

Communication board

Computer

Operator Computer

Unit

Haptic Device

Ethernet (Wireless)

Fig. 2: Hardware structure of DYROS-JET.

robot’s neck in yaw and pitch, and two actuators are usedto control its waist. The robot has a total of 30 DoF, and itsnominal power consumption during the stand-by squat poseis approximately 200 W.

B. Actuator

Robotis Dynamixel PRO [13] smart actuators are usedfor DYROS-JET. The use of smart actuators allows for amodular design of the robot; however, it may hinder itsoptimal design. A Robotis Dynamixel PRO actuator includesa communication device, a controller, a transmission device,and a motor in one module. It uses the RS-485 communica-tion standard, which allows multiple devices to be connectedin parallel, thus improving the system’s communicationcapabilities. In contrast, the maximum communication speedis limited1, and the request to and response from the actuatorcannot be synchronized. Therefore, we must consider theresponse delay when selecting the communication frequencybecause the response delay increases when the actuators arein motion, as shown in Fig. 4.

The RS-485 communication standard can be used in thecomputer in two different ways: using a USB to RS-485converter and using a serial RS-485 PCI expansion card.The USB to RS-485 converter uses a virtual serial driver,but no real-time driver for the converter exists. Hence,THORMANG has a control frequency of up to 100 Hz whenusing the USB to RS-485 converter [12]. Therefore, we haveestablished the RS-485 communication environment throughthe PCIe bus for its low latency and periodic communication.The serial RS-485 PCIe expansion card is the DS-MPE-SER4M of Diamond systems, which uses the XR17V354chipset. Consequently, we achieved a maximum controlfrequency of 333 Hz without a large margin for the response

1Dynamixel PRO supports up to a 10.5 M baud rate.

delay, and 200 Hz was determined a stable control frequencyfor the majority of our controllers.

C. Sensors

• LIDAR: The Hokuyo UTM-30LX LIDAR sensor isused for terrain recognition and simultaneous localiza-tion and mapping (SLAM). This sensor transmits datathrough an Ethernet TCP/IP communication channeland is rotated by 360◦ using an additional motor toprovide three-dimensional information. In this case,a slip ring is used to enable perpetual rotation at aconstant speed.

• Stereo Camera: We used the ZED stereo camera forobject recognition together with SLAM. We used theembedded computing device Jetson TX2 because ofthe ZED SDK requires CUDA (a parallel computingplatform and programming model invented by NVIDIA)to compute a depth map in real-time.

• Inertial Measurement Unit (IMU): We used the Mi-crostrain 3DM-GX4-45 IMU system to obtain dataregarding the acceleration, angular velocity, and orienta-tion of the robot’s pelvis. These data are used to improveSLAM and gait control.

• Force–torque Sensor: The robot’s ankle was con-structed to place a force–torque sensor for measuring theforce and torque exerted on the feet. In THORMANG,the robot control unit (RCU) receives the sensor datathrough Dynamixel PRO actuator. The actuator hasan analog to digital converter but it only receives asingle-ended analog signal, which is vulnerable to signalnoise due to the noise of the reference voltage thatoccurs during motor control. To overcome the signalnoise, DYROS-JET treats the sensor signal in a differentway. The power supplied to the force–torque sensor isseparated from the power source that drives the motor,and the sensor outputs a differential analog signal that

747

Page 3: System Design of Humanoid Robot DYROS-JETdyros.snu.ac.kr/wp-content/uploads/2019/01/0170.pdf · manoid robot. We separate theses aspects into the following three major categories.

Modules Using ROS Environment

Hardware Interface

DAQ

ExternalEncoder

LIDAR Real-time tasks

Human Robot Interaction

Haptic Device

Graphic User Interface

rt_dynamixel

DXL channel #1

Finite State Machine(SMACH)

Robot Controller

URDFModel

Robot Model Updater

Controller Modules

Controller Modules

Controller Modules

Simulation Interface

𝒒𝑑𝑒𝑠𝑖𝑟𝑒𝑑

Sensory data

V-REP

V-REP ROS Interface

Real Hardware

IMU

Stereo Camera

Fig. 3: Software structure of DYROS-JET.

Request from RCU

Response from Dynamixel PRO

Fig. 4: Communication signals in the RS-485 bus: normalsignals when the actuators are in the idle state (upper), anddelayed signals when the actuators are in motion (lower).

is more robust against the noise. To acquire this signal,we used Sensoray 826 data acquisition device that canbe installed in a computer.

• External Joint Encoder: The actuators of the hu-manoid robots inevitably have compliance in their jointmechanism. In particular, the Dynamixel PRO actuatorhas high compliance that affects the walking perfor-mance of the robot; hence, external joint encoders areinstalled to measure the joint angles [6]. To accountfor the six DoF that DYROS-JET has per leg, sixexternal encoders are installed for each leg. To obtainthe value of the external encoder, we used the FRDM-K64F digital signal processor (DSP) with a quadraturedecoder. The DSP has a clock frequency of up to 120MHz and can transmit the encoder value to anotherdevice with a frequency of up to 2 KHz. As shownin Fig. 5, the DSP at the robot’s foot periodically

DSP(Trigger)

DSP

DSP

DSP

DSP

DSP(Collector)

Encoder

Encoder

Encoder

Encoder

Encoder

Encoder

Asynchronous Serial Comm.

UDP/IP (Ethernet)

DSP(Collector)

Encoder Switch Router

Quadrature Encoder Signals

Fig. 5: Structure of the external encoder.

transmits the encoder value to the next DSP. When thenext DSP receives the packets, it transmits the encodervalues, including the encoder value of the current joint.This transmission continues until all encoder valuesarrive at the top-level DSP. Each DSP transmits thesevalues using asynchronous serial communication. Thetop-level DSP converts the values of all encoders intothe user datagram (UDP) protocol and transmits them tothe RCU via Ethernet. We used an additional networkswitch owing to the large number of Ethernet devicesincluded in the robot.

D. Computer Units

The robot has two computer units, the robot control unit(RCU) and the robot perception unit (RPU). The RCU com-prises an Intel (R) Core (TM) i7-4770K 3.5 GHz processor,8 GB RAM, and a mini-ITX size motherboard. DYROS-JETuses six threads in its control: one thread is devoted to non-

748

Page 4: System Design of Humanoid Robot DYROS-JETdyros.snu.ac.kr/wp-content/uploads/2019/01/0170.pdf · manoid robot. We separate theses aspects into the following three major categories.

real-time and slow computation for motion planning, anotherthread is used for real-time control, and the four remainingthreads are used for actuator communication. Bottlenecksmay affect motor communication; hence, to avoid the same,we used a processor with eight physical threads.

We configured the RCU such that it will achieve maximumperformance even on small-sized computers by using mini-ITX form-factor motherboard, which is a ready-made systemin which CPU can be changed. Owing to its small size,however, most mini-ITX motherboards have only one PCIeslot, and the number of external devices is limited. To expandthe PCIe bus channel, we use the M.2 and the mSATA/PCIedual-purpose slot that can provide an additional PCIe buschannel. Each slot can connect one PCIe device througha conversion adapter; hence, herein, two PCIe devices areinstalled, the RS-485 communication device and the dataacquisition device.

For the RPU to implement perception algorithms, parallelcomputation procedures must be implemented. To this end,we use the NVIDIA Jetson TX2 device, which has 256CUDA cores that enhance computation. The RPU transmitsthe computed results to the RCU through an Ethernet con-nection.

E. Software System

We use the Xenomai real-time Linux kernel, with Ubuntu14.04 as the operating system to reduce latency duringcontrol. As shown in Fig. 3, the software system comprisesfour parts, the Human–Robot Interaction (HRI) interface,robot controller, hardware interface, and simulation interface.Each part contains multiple modules that use the ROSenvironment.

In the HRI part, a haptic device node and a graphic userinterface node publish a command message to interact withthe robot. To prevent unintended behavior, the state machinecontrols the flow of messages.

The command published from the HRI part is transmittedto the robot controller part, which includes a robot model up-dater and a controller module. The model update module usesthe rigid body dynamics library [14] based on the unifiedrobot description format (URDF) to update current dynamicsand kinematics. The controller modules then compute thedesired joint positions required to execute the commandpublished by the HRI part.

The hardware interface and simulation interfaces are con-nected to the actual robot and the simulation, respectively.The hardware interface comprises a data acquisition node,a LIDAR node, a stereo camera node, an IMU node, anexternal encoder node, and a real-time Dynamixel node.These nodes provide interfaces for the hardware using hard-ware abstraction. In the simulation interface, the V-REP ROSinterface connects the ROS environment and V-REP.

We selected V-REP as a simulator, as presented in [15],owing to its potential to the Vortex engine, which is morestable in a contact situation than other available engines.

F. Fail-safe

The controller must have a fail-safe algorithm to preventthe whole system from failing. We assigned priority levelsto the controllers that determine the access priority for thecommon resource, i.e., the desired joint position(qdesired) toimplement such an algorithm. A controller with high prioritycan override a controller with low priority; in such a case, thelow-priority controller deactivates itself. With this structure,any controller that exhibits a malfunction can be overriddenby a reliable controller. Thus, preventing unexpected errorsand problems due to user error is possible using the multi-step safety algorithm described herein.

The controllers used in DYROS-JET comprise severalmodules that realize mobility and manipulability, such as thejoint space controller, which creates and controls trajectoriesin the joint space, and the task space controller, whichcreates and controls trajectories in the task space. Becausethe joint space controller does not possess singularity duringcomputation, we assigned the highest priority to the jointspace controller. As a result, when an error occurs in anothercontroller, the joint space controller can be executed toterminate the other controller and return to the initial jointposition or an arbitrarily designated position.

III. VERIFICATION AND APPLICATIONThe proposed system for DYROS-JET was verified using

two experiments, a latency test and a fail-safe test. Todetermine the control frequency of the robot, we measuredthe latency in communication, whereas the time between thecommand request and the joint state response was measuredto obtain the latency of the actuator communication. Themeasured latency includes the electrical response delay, theserial device driver delay, and the packet decoding delay.This experiment was performed under the following condi-tions. Eight actuators were connected to the communicationbus and the communication frequency was set to 200 Hz.We sampled 10,000 latency samples, and found that themaximum latency of the communication system is approxi-mately 2.818 ms, which is 56.3% of the control period andeffectively verifies that the margin of the communication isenough. Hence, we selected 200 Hz as the control frequencyto minimize the packet loss. Figure 6 summarizes our results.

The fail-safe algorithm with the control priority wasverified through the following experiment, which is summa-rized by the data measured when the joint space controlleroverrides the task space controller, as presented in Fig. 7.Initially, the task space controller controlled the joints of theright arm. Then, 5 s after the beginning of the experiment,the higher priority joint space controller was enabled, whichoverrode the task space controller. As the result, the targetposition and the trajectory of joints were changed and thetask space controller terminated normally. However, a smalldiscontinuity was observed in the joint velocities, stemmingfrom the new trajectory reflecting the current state. Uponactivation of the joint space controller, the target trajectoryis generated from the current position and velocity. Becausethe tracking of the desired position had not been completely

749

Page 5: System Design of Humanoid Robot DYROS-JETdyros.snu.ac.kr/wp-content/uploads/2019/01/0170.pdf · manoid robot. We separate theses aspects into the following three major categories.

2.3 2.4 2.5 2.6 2.7 2.8 2.9 3

Latency (ms)

0

200

400

600

800

1000

1200

1400

Counts

Fig. 6: Latency of the actuator communication.

0 1 2 3 4 5 6 7 8 9 10-2

-1

0

1

Join

t positio

n (

rad)

Joint 1

Joint 2

Joint 3

0 1 2 3 4 5 6 7 8 9 10

Time (s)

-0.2

-0.1

0

0.1

0.2

Join

t velo

city (

rad/s

)

Joint 1

Joint 2

Joint 3

Fig. 7: Joint position and velocity when the controller isoverridden by a higher priority controller of joint spacecontrol.

accomplished owing to the control performance, a smalldifference occurred between the desired and actual positions.This discrepancy created the small discontinuity in the jointvelocity, but for all practical purpose, its effect is negligible.

The humanoid robot DYROS-JET using the proposedsystem has been successfully used to perform various tasks.For example, Kim et al. proposed a control scheme forlocomotion, and conducted experiments with DYROS-JET[6]. They constructed a linear feedback controller, whichcompensates disturbance and gravity using the internal andexternal encoder. This system provides manipulation taskusing MoveIt! motion planning framework [16], which gen-erates the joint trajectory that the controller module uses tocontrol the robot. Several related manipulation tasks havebeen presented in [17].

IV. CONCLUSIONWe introduced a system design for a humanoid robot,

DYROS-JET, using the Dynamixel PRO as an actuator.

We analyzed the communication system of the actuatorand obtained high control frequency through a PCIe RS-485 interface. In addition, we introduced interfaces thatinterconnected the sensors of the robot. A software systemand a controller with a fail-safe algorithm were used toprevent unexpected errors. The efficiency of the proposedsystem was experimentally verified.

REFERENCES

[1] M. A. Diftler, J. Mehling, M. E. Abdallah, N. A. Radford, L. B.Bridgwater, A. M. Sanders, R. S. Askew, D. M. Linn, J. D. Yamokoski,F. Permenter, et al., “Robonaut 2-the first humanoid robot in space,” inRobotics and Automation (ICRA), 2011 IEEE International Conferenceon. IEEE, 2011, pp. 2178–2183.

[2] K. Kaneko, F. Kanehiro, M. Morisawa, K. Akachi, G. Miyamori,A. Hayashi, and N. Kanehira, “Humanoid robot hrp-4-humanoidrobotics platform with lightweight and slim body,” in IntelligentRobots and Systems (IROS), 2011 IEEE/RSJ International Conferenceon. IEEE, 2011, pp. 4400–4407.

[3] Y. Sakagami, R. Watanabe, C. Aoyama, S. Matsunaga, N. Higaki, andK. Fujimura, “The intelligent ASIMO: System overview and integra-tion,” in Intelligent Robots and Systems, 2002. IEEE/RSJ InternationalConference on, vol. 3. IEEE, 2002, pp. 2478–2483.

[4] H.-O. Lim, S. A. Setiawan, and A. Takanishi, “Position-basedimpedance control of a biped humanoid robot,” Advanced Robotics,vol. 18, no. 4, pp. 415–435, 2004.

[5] A. Schmitz, M. Maggiali, L. Natale, B. Bonino, and G. Metta, “Atactile sensor for the fingertips of the humanoid robot icub,” inIntelligent Robots and Systems (IROS), 2010 IEEE/RSJ InternationalConference on. IEEE, 2010, pp. 2212–2217.

[6] M. Kim, J. H. Kim, S. Kim, J. Sim, and J. Park, “Disturbance observerbased linear feedback controller for compliant motion of humanoidrobot,” in Robotics and Automation (ICRA), 2018 IEEE InternationalConference on. IEEE, 2018, pp. 403–410.

[7] M. Quigley, K. Conley, B. Gerkey, J. Faust, T. Foote, J. Leibs,R. Wheeler, and A. Y. Ng, “ROS: an open-source robot operatingsystem,” in ICRA workshop on open source software, vol. 3, no. 3.2.Kobe, Japan, 2009, p. 5.

[8] P. Allgeuer, H. Farazi, M. Schreiber, and S. Behnke, “Child-sized3d printed igus humanoid open platform,” in Humanoid Robots (Hu-manoids), 2015 IEEE-RAS 15th International Conference on. IEEE,2015, pp. 33–40.

[9] G. Ficht, P. Allgeuer, H. Farazi, and S. Behnke, “NimbRo-OP2:Grown-up 3d printed open humanoid platform for research,” in Hu-manoid Robotics (Humanoids), 2017 IEEE-RAS 17th InternationalConference on. IEEE, 2017, pp. 669–675.

[10] I. Ha, Y. Tamura, H. Asama, J. Han, and D. W. Hong, “Developmentof open humanoid platform DARwIn-OP,” in SICE Annual Conference(SICE), 2011 Proceedings of. IEEE, 2011, pp. 2178–2181.

[11] S. Kim, M. Kim, J. Lee, S. Hwang, J. Chae, B. Park, H. Cho, J. Sim,J. Jung, H. Lee, et al., “Approach of team snu to the darpa roboticschallenge finals,” in Humanoid Robots (Humanoids), 2015 IEEE-RAS15th International Conference on. IEEE, 2015, pp. 777–784.

[12] ——, “Team snu’s control strategies for enhancing a robot’s capability:lessons from the 2015 darpa robotics challenge finals,” Journal of FieldRobotics, vol. 34, no. 2, pp. 359–380, 2017.

[13] Dynamixel pro. [Online]. Available: http://www.robotis.us/dynamixel-pro/

[14] M. L. Felis, “RBDL: an efficient rigid-body dynamics library usingrecursive algorithms,” Autonomous Robots, pp. 1–17, 2016. [Online].Available: http://dx.doi.org/10.1007/s10514-016-9574-0

[15] S. Ivaldi, V. Padois, and F. Nori, “Tools for dynamics simula-tion of robots: a survey based on user feedback,” arXiv preprintarXiv:1402.7050, 2014.

[16] I. A. Sucan and S. Chitta, “Moveit!” 2013. [Online]. Available:http://moveit.ros.org

[17] S. Kim. (2018) Dyros jet: Tele-manipulation. [Online]. Available:https://www.youtube.com/watch?v=9UwJQREUjtc

750