and Manufacturing Science and Technology Center ... The architecture of the platform is being made open ... we call the package of the simulator and controllers.
OpenHRP: Open Architecture Humanoid Robotics Platform Hirohisa Hirukawa Fumio Kanehiro and Shuji Kajita National Institute of Advanced Industrial Science and Technology, METI. 1-1-1 Umezono, Tsukuba, Ibaraki, 305-8568 Japan Abstract This paper introduces an open architecture humanoid robotics platform (OpenHRP for short) on which various building blocks of humanoid robotics can be investigated. OpenHRP is a virtual humanoid robot platform with a compatible humanoid robot, and consists of a simulator of humanoid robots and motion control library for them which can also be applied to a compatible humanoid robot as it is. OpenHRP also has a view simulator of humanoid robots on which humanoid robot vision can be studied. The consistency between the simulator and the robot are enhanced by introducing a new algorithm to simulate repulsive force and torque between contacting objects. OpenHRP is expected to initiate the exploration of humanoid robotics on an open architecture software and hardware, thanks to the unification of the controllers and the examined consistency between the simulator and a real humanoid robot.
1
Introduction
The Ministry of Economy, Trade and Industries of Japan has run Humanoid Robotics Project (HRP for short) since 1998 for five years [4, 5]. The leader of HRP is Hirochika Inoue from the University of Tokyo, and Manufacturing Science and Technology Center (MSTC) is the secretary of the project. Four copies of a humanoid robot (called HRP-1), teleoperations cockpit for them and a virtual humanoid robot platform (V-HRP for short)[11, 12] had been developed in phase one of HRP as the research platform, and various applications of humanoid robots are under development in phase two on the platform. We call the organization of the project platform-based approach. It is the antithesis of usual robotics projects in which elementary technologies are developed at first and they are integrated into a system at the final stage. The architecture of the platform is being made open, step by step. The software of HRP-1 have been
developed by Honda R&D as well as its hardware, and it is provided as a black box. We have replaced the controller for biped locomotion by our own one which has been developed on V-HRP. Besides, V-HRP has also been replaced by a new simulator on which we can develop the controllers portable to the hardware without any modification. Finally, a new humanoid robot HRP-2 is to be developed, and the controllers examined on HRP-1 will be applied to HRP-2. The simulator is build on CORBA[16] which is a standard software architecture, and the realtime controller of the robot is run on ART-Linux[6] which is a realtime extension of Linux. Besides, the simulator and the controllers are now white boxes. Therefore, we call the package of the simulator and controllers with the compatible humanoid robot OpenHRP which stands for Open Architecture Humanoid Robot Platform. The unification of the controllers for the simulated and real robot is realized by hardware abstraction and synchronization mechanism and employing ARTLinux in which realtime processing is available at the user level. Thanks to the unification, the controllers can share significant amount of software with the simulator, including the parameter parser, kinematics and dynamics computations and the collision detector. The consistency between the simulation and experiments is enhanced by introducing a new algorithm to simulate repulsive force and torque between contacting objects even when soft spring-damper mechanism is embedded in the feet of a humanoid robot. This is essential since that of HRP-1 is very soft. Because the unification of the controllers and the consistency between the simulated and real robots are realized, OpenHRP can be a useful virtual platform for humanoid robotics on which various fundamental technologies can be developed. The virtualization of the platform is very important to inherit software library from one hardware to another efficiently. For example, Honda R&D took only nine months or so to replace humanoid robot P2 by P3, since Honda R&D also has a nice virtualized platform and most software
could be ported with the minimum effort. This paper is organized as follows. Section 2 overviews the configuration of OpenHRP and that of HRP-1. Section 3 presents how the unification of the controllers for the simulator and the real robot is realized. Section 4 introduces how to isolate the nonrealtime ORB for sharing the codes of the simulator with those of the realtime controller and a realtime collision detector is presented as an example of the code sharing. Section 5 shows examples of the simulation and experiments. Section 6 concludes the paper.
2 2.1
Overview of OpenHRP Configuration of OpenHRP
The configuration of OpenHRP is shown in Fig.1. OpenHRP can simulate the dynamics of structurevarying kinematic chains between open chains and closed ones like humanoid robots[15]. It can detect the collision between robots and their working environment including other robots very fast and precisely on which the forward dynamics of the objects are computed. It can also simulate the fields of vision of the robots, force/torque sensors and gradient sensors according to the simulated motions. We call the simulations sensor simulations. The sensor simulations are essential to develop the controllers of the robots. OpenHRP is implemented as a distributed object system on CORBA(Common Object Request Broker Architecture)[16]. A user can implement a controller using an arbitrary language on an arbitrary operating system if it has a CORBA binding. The dynamics simulator of OpenHRP consists of five kinds of CORBA servers (see Fig.1) and these servers can be distributed on the Internet and executed in parallel. Each server can be replaced with another implementation if it has the same interface defined by IDL (Interface Definition Language). Using the language independence feature of CORBA, ModelParser and OnlineViewer are implemented using Java and Java3D, other servers are implemented using C++. The functions of each server are as follows. ModelParser This server loads a VRML file describing the geometric models and dynamics parameters of robots and their working environment, and provides these data to other servers. CollisionChecker The interference between two sets of triangles is inspected, and the position, normal
vector and the depth of each intersecting point are found. RAPID[1] is enhanced to this end. Dynamics The forward dynamics of the robots are computed. Controller This server is the controller of a robot, which is usually developed by the users of OpenHRP. OnlineViewer The simulation results are visualized by 3D graphics and recorded. Using the servers, the forward dynamics of the robots are computed in the following procedure. The total control flow is shown in Fig.1. Setting up of the simulation environment (1) ModelParser reads a VRML file via HTTP protocol. The kinematics and dynamics parameters are sent to DynamicsServer and the geometric model is to CollisionChecker. Execution of the dynamics simulation (2) Controller reads the outputs of the simulated sensors while communicating with DynamicsServer. (3) Let Controller and DynamicsServer execute the computations. Note that these computations can be run in parallel. The outputs of Controller are the torques of the actuators, and those of DynamicsServer are the updated states of the robot. (4) While the forward dynamics is computed, CollisionChecker is called to find the position, normal vector, and the depth of each intersecting point. (5) After these computations, let Controller send the control outputs to DynamicsServer. (6) Controller sends the outputs to DynamicsServer. Visualization and recording (7) Acquire the current states of the world from DynamicsServer. (8) Send them to OnlineViewer which visualizes the simulated world and records it. In order to evaluate the performance of OpenHRP, biped locomotion of a humanoid robot is simulated. The sample humanoid robot has 6DOF arms, 6DOF legs, 3DOF waist, 2DOF neck and 29DOF in total. The interference between every links of the humanoid and the ground is checked and the interference between a foot link and the ground always occurs during the simulation. The specifications of the used computer include CPU:Intel PentiumIII 933MHz, Memory:512MB, and OS:Linux-2.2.17. The computation time except the visualization is 25[ms] per the unit integration time, which is usually set around 1 [ms].
7 3 CollisionChecker
2 ModelParser
9 Dynamics
ORB
Controller
OnlineViewer
5
3 1 6
10
4 6 8
1 11
Simulator Main
Figure 1: OpenHRP Overview
2.2
Humanoid robot HRP-1S
As an example of compatible humanoid robots with the simulator, HRP-1 is investigated in this paper. The configuration of the controller hardware of humanoid robot HRP-1 is shown in Fig.2. The humanoid robot is called HRP-1S in the following to clarify that the Honda controller is replaced by our own one. The realtime controller runs on a CPU board in
HRP1S Controller
Body int Virtual World Simulated by V-HRP
Body in Real World
Robot Platform HRP1S
Wireless LAN 2Mbps
CPU Board(Body Control) Intel PentiumIII 800MHz 512MB Memory y 128MB Compact Flash
Figure 3: Shared controller for virtual and real robots
Honda I/O Board ternet Image Capture Board CPU Board(Image Processing)
PC(Real Time Monitor) Reflective Memory
iber Optic etwork .2Mbyte/s
I/O Board Reflective Memory
Figure 2: Controller hardware of HRP-1S the backpack of HRP-1S, whose operating system is ART-Linux. Using the optical fiber network connecting the pair of the reflective memory mounted on the backpack and the PC outside the robot, the internal states of the robot can be monitored at the PC in realtime.
3
Unification of the controllers
As mentioned above, the controllers developed on OpenHRP can be applied to the real counterpart without any modification. This concept is illustrated in Fig.3. The unification of the controllers for the virtual and real robot has been realized by introducing software adapters for two robots respectively and employing ART-Linux on which real-time processing is
available at the user level. This is a distinguished feature, considering that RT-Linux[17] realizes it only at the kernel level. Thanks to this feature of ART-Linux, users can implement realtime applications as if they are non-realtime ones. This is the first key to realize the identical controller for the virtual and real robot. By the unification, the controllers can share softwares with the dynamics simulator of OpenHRP, including the parameter parser, kinematics and dynamics computations and the collision detector. This feature can make the development of the controllers more efficient and the developed controllers more reliable. Besides, it becomes easier to feedback the experimental results for the improvements of the dynamics simulator when the run-time environments of the controllers are identical. The controller must be implemented by exactly same methods with the same signatures for the virtual and real robots, to realize the unification of the controllers; the following two requisites must be hold to this end. (1) abstraction of the controller API where the software body looks like the same as the hardware body, and (2) a synchronizing mechanism that can absorb the difference between the speed of time in the simulated and the real world. The tricks to satisfy these requisites are described in the following.
The unification of the controllers does not make sense if the results of the dynamics simulation are not consistent with those of the experiments. The soles of HRP-1 is very soft because a spring-damper mechanism is embedded in each foot. We have developed an algorithm to simulate general spring-damper mechanisms precisely to keep the consistency, which is also presented in the following.
3.1
Unification architecture
class robot_adaptor { public: virtual bool open(int argc, char *argv[]); virtual bool close(); virtual bool read(robot_state *rs); virtual bool write(motor_command *mc); };
3.1.2 3.1.1
Hardware abstraction
The first requisite is realized based on the plug-in architecture [13], where application software is separated into two layers at the adapter level and the counterpart beyond the adapter can be replaced. The software architecture of simulated HRP-1S and the real one is shown in Fig.4. The controller API of OpenHRP is not identical with that of Honda I/O board shown in Fig.2. The unification of a controller Simulation Phase
Controller Main Routine
Simulated Body Collision Checker
Model Parser
Dynamics
ORB
Experiment Phase Model Parser
Online Viewer
HRP1S Emulation Adaptor V-HRP Controller
Controller Main Routine HRP1S Hardware Adaptor
ORB
I/O library HRP1S Hardware
Figure 4: Software architecture of simulated and real humanoid robot HRP-1S is realized by introducing the adapter whose API is the abstracted controller API mentioned above. The emulation adapter is layered on the controller API of OpenHRP which reads the outputs of the sensor simulators and write the inputs of DynamicsServer, and the hardware adapter is put on the API of Honda I/O board of HRP-1S. The API of the adapters is identical shown as follows.
Synchronization mechanism
Though various speedup techniques for the dynamics simulation have been proposed to the present, but it is still difficult to compute the forward dynamics of robots with many degrees of the freedom including the visualization in realtime. Generally speaking, time goes by at a slower speed in the simulated world than in the real world. Besides, the speed is not constant in the virtual world due to the fluctuation of the required computation time. Therefore, the synchronization mechanism of the controller must not be embedded in the main logic of the controller, but in the hardware adapter. Then the adapter can manage a change of the speed of time by a synchronization mechanism. Note that the outputs of the controller can not always be updated in time in the real world. So it is possible that the controller fails to handle the robot even when it has succeed to move the robot in the virtual world.
4
Determining the repulsive force
4.1
Finding the interference state
We have proposed a complete algorithm to find the constraints which is imposed on a polyhedral object in contact with another[2]. The key idea to determine the constraints is finding separating planes between the neighborhoods of a contact point in two objects. But there are two reasons why the complete algorithm does not work to find the interference state in the dynamics simulation. • CollisionChecker detects the interference between two sets of triangles which are obtained from the decomposition of the boundary representation of two objects under consideration. Then the topological information between the triangles has been lost, and it is not possible to analyse the neighborhoods for finding the separating planes.
• The objects may penetrate each other during the numerical dynamics simulation, and therefore no separating plane exists between the neighborhoods any more. The first problem can be bypassed if we don’t decompose the geometric models into the sets of triangles, but the geometric analysis must become very heavy. There is no way to avoid the second one, when we simulate the dynamics on a floating point arithmetic. Therefore, the only option for us is finding a ‘reasonable’ constraint at each intersecting point. Because CollisionChecker detects the interference between two sets of triangles, it is enough to have an algorithm for the purpose that works for an intersecting pair of triangles. At first, Algorithm 3.1 classifies the interference state into two cases. Algorithm 3.1 1. If one triangle intersects at two relative internal points of another triangle, the interference state is vertex-face penetration. 2. If an edge of one triangle penetrate another triangle and vice versa, the interference state is edgeedge penetration. Here, a relative internal point is an internal point of a triangle on its supporting plane. These two cases are illustrated in Fig.5 where the left corresponds to the first case and the right the second. The arrows represent the constraining normal vector at the penetrating point from a triangle to another respectively.
Figure 5: Vertex-face and edge-edge penetration The vertex-face penetration can be classified further into two cases. The first case occurs when a triangle is almost coplanar with a triangle of the penetrated object, and the second case does when a triangle is rather perpendicular to another. See Fig.6. Note that these cases can not be classified only by the topological state between the triangles. The difference between two cases in Fig.6 is the geometrical relationship.
Figure 6: Two types of vertex-face penetration The two cases are classified and the constraining vector at penetrating points is determined by Algorithm 3.2. In the following, let n be the normal vector of the penetrating triangle p1 p2 p3 on the object whose motions are under consideration, and m be the normal vector of the penetrated triangle q1 q2 q3 on the other objects. Algorithm 3.2 1. If the intersecting points between the triangles is enough close to the penetrating vertex, return m. 2. If the orthogonal projection of the penetrating vertex onto the supporting plane of q1 q2 q3 is a relatively outside point of q1 q2 q3 , return -n. 3. Find the penetrating depth along m and n respectively, return the normal vector with the smaller depth. In Step 3, the depth of a penetrating point is defined by the Euclid distance between the point and the supporting line of the penetrated edge for the constraining vector n, and the smaller depth is taken from two penetrating points. The distance between the penetrating point and the supporting plane of q1 q2 q3 is defined to be the depth of the point for the constraining vector m. The edge-edge penetration case is examined next. In the case, it is trivial to determine the constraining vector, but difficult to judge its direction. Let p1 p2 and q1 q2 be the penetrating edges, and l be (p2 − p1 ) × (q2 − q1 ). Then the constraining vector is l or −l. The sign is determined by Algorithm 3.3. Algorithm 3.3 Let r be the intersecting point between p1 p2 p3 and q1 q2 . 1. If n · m > 0 then return 2. If (p3 − r) · (q3 − r) > 0 then return 3. c1 ← n · l/(|n||l|) 4. c2 ← (p3 − r) · l/(|p3 − r||l|)
5. c3 ← m · l/(|m||l|) 6. c4 ← (q3 − r) · l/(|q3 − r||l|) 7. If |c2 | < and |c4 | < then If |c1 | < |c3 | then return m else return −n 8. If c2 c4 > 0 return 9. If |c1 | < |c2 | then c12 ← c2 else c12 ← −c1 10. If |c3 | < |c4 | then c34 ← −c4 else c34 ← c3
Figure 8: Foot of a robot is on a plate.
11. If |c12| < |c34 | then c ← c34 else c ← c12 12. If c > 0 then return l else return −l Step 1 and 2 reject a pair of the triangles that does not face each other even if the pair is intersecting, since there must exists another pair of the triangles that faces between the non-facing pair. Otherwise, the non-facing pair can not intersect. See Fig.7. Step 3-6
Figure 7: The cases in which the applicability conditions are violated evaluate several angles to determine the direction of the normal vector l. When c2 and c4 are small, it is trivial that two triangles are almost coplanar. Then the algorithm returns the normal vector of the triangle that is more parallel to l. This is Step 7. Step 8 examines if two triangles are separated by the plane with the normal vector l that passes through r, and reject the pair of the triangles if the result is negative. Step 9-11 finds the most reliable angle to determine the direction of l. Finally, Step 12 determines the direction. Step 12 is robust, because the absolute value of c2 or c4 is larger than , and therefore that of c is as well. In the case of the edge-edge penetration, the depth of the penetration is defined by the length of the common perpendicular to the supporting lines of p1 p2 and q1 q2 . An example of the obtained interference state is shown in Fig. 8 where the arrows represent the constraining vector for the foot of the robot. Notice that the left penetrating point is an intermediate point on the edge.
4.2
Finding the repulsive force
This section presents how to assemble the interference date obtained by the above geometric algorithm for finding the repulsive force between the objects. Let ni : 3 × 1, i = 1 · · · M be the constraining vector at the i-th penetrating point, pi : 3 × 1, i = 1 · · · M the position of the point, and di : 3 × 1, i = 1 · · · M the depth of the point, where M is the cardinal number of the penetrating points. Then we try to find the infinitesimal translation ∆X : 3 × 1 and rotation Ω : 3 × 1 of the constrained object which make the objects at the interference state from the contact state without the overlapping of their inside. In other words, we want to find the infinitesimal screw of the object which make the depth at the penetrating points as close as possible. This problem can be formulated as the following minimization problem.
subject to
minimize E T E ∆X A ≥ 0, Ω
where E=A A=
nT1 nT2 .. .
nTM
∆X Ω
(1)
− D,
(p1 × n1 )T (p2 × n2 )T .. .
(pM × nM )T −d1 −d2 D = . . .. −dM
(2)
(3)
(4)
This is a linear programming problem with a nonlinear objective function, and can be solved by many package
software. An alternative way is finding the solution with the least square error by ∆X = A+ D, (5) Ω where ()+ stands for the pseudo inverse of a matrix, and projecting the solution orthogonally onto the polyhedral convex cone defined by inequality (1). The current implementation uses the latter way. Then the spring element of the repulsive force is found by ˆ F ∆X = −K , (6) ˆ τ Ω where F and τ are the force and torque respectively, ˆ and Ω ˆ are K : 6 × 6 a spring constant matrix and ∆X the solution of the above minimization problem. The algorithm to find the damper element is examined next. Let V0 and ω0 be the relative translational velocity and the angular velocity between the objects in contact respectively. Then the proposed algorithm finds the orthogonal projection (V˜ , ω ˜ ) of (V0 , ω0 ) onto the polyhedral convex cone defined by V A ≥ 0. (7) ω The damper force along the normal vector at the penetrating points is computed from (V˜ , ω ˜ ) based on a nonlinear damper model [3, 7] by F ∆X n V˜ = −λ , (8) ˜ τ Ωn Ω where λ = 32 αK, α is a constant defining the linear dependence of the coefficient of restitution on the impact velocity, and the n-th power of a vector is defined by the vector whose elements are the n-th power of the original elements respectively. In the nonlinear model, the damping is dependent on the penetration depth, and then the damping increases with the depth of the penetration continuously as the objects is coming into contact[3, 7]. This feature is essential to simulate the biped walking in which a foot of the robot collides the floor at a finite velocity. The damper force along the tangent vector can be found from the projection (V¯ , ω ¯ ) of (V0 , ω0 ) into the null space of the coefficient matrix of the left hand side of inequality (7) by F V¯ = −C , (9) ¯ τ Ω where C : 6 × 6 is the damper coefficient matrix to simulate the tangent force generated by the friction.
In total, the repulsive force and torque by the spring-damper model is given by ˆ ˆ n V˜ V¯ F ∆X ∆X −C . = −K −λ ¯ ˆn ω ˆ Ω τ ˜ Ω Ω (10) Note that the final output is the orthogonal projection of the force and torque in Eq.(10) onto the polyhedral convex cone defined by an enhanced inequality of (1) in which the friction cones are taken into account. The projection is necessary to avoid the generation of the force which is outside the friction cone at each contact point.
5 5.1
Sharing software between the simulator and the controllers Isolation of ORB
The controller and the dynamics simulator can share significant amount of codes. For example, collision detection is one of major building block of the simulator, and it is also essential in the controller to avoid the self-collision of a moving humanoid robot. It is needless to say that basic vector and matrix operations are included both the simulator and the controller. The parameters parser can also be shared. The forward kinematics computation of robots are common too. The unified controller makes the code sharing easier, and therefore the development of the controllers more efficient. Another good news of the code sharing is that the controllers can be more reliable since the building blocks borrowed from the simulator has been already examined intensively by the simulation. However, there is a barrier to reuse the code in the controller. That is, the servers like CollisionChecker or DynamicsServer are implemented as CORBA servers as shown in Fig.1. Though realtime functions are included in the specifications of CORBA since version 2.4 and we can find the implementations of the functions, but the overhead of IIOP (Internet InterOrb Protocol) used in CORBA is not small enough for the controller which must update the outputs at a few milli-seconds. This overhead can be bypassed by the following architecture. Let the servers like CollisionChecker or DynamicsServer consist of two layers. The lower layer is a normal library which is independent to CORBA, and the higher layer wraps the library by CORBA interface and converts the data structures between the library and the interface. For example, these servers
call ModelParser through the ORB when reading a VRML file describing the parameters of robots, but they access non-CORBA interfaces when they control the robots in realtime. The internal configuration of the controller is shown in Fig.9. ModelParser Geometry
ORB
Kinematics,Dynamics
Controller CORBA Interface Collision Check Library (RAPID)
CORBA Interface Controller Main Routine
Dynamics Library
Figure 9: Internal configuration of the controller
5.2
3. While keeping the joint of the arms within the safe region, check the self-collision in realtime only for the suspicious pairs. In the case of HRP-1S, we need not check the collisions between the arm and the leg in the same side if we keep the pitch joint of the shoulder or the roll joint in the safe range. There is no significant safe range for the collision between the left and right legs, but each roll link of the hip and each pitch link of ankles are covered by the other links and therefore need not be checked. We assume that only legs are moving during walking, 16 pairs must be checked between the legs, 16 pairs between two links around the hands and the legs, 4 pairs between the main body and foot links, and 36 in total, which can be done in realtime. An example posture while walking is shown in Fig.10. An exper-
Realtime collision checker
A realtime collision checker is presented here as an example of shared codes between the simulator and the controller. When a humanoid robot is moving, it is desirable that the self-collision between the links of the robot is checked in realtime for enabling emergency stopping of the robot. Let N be the number of the links of a humanoid robot. Then the number of pairs of the links is (N 2 ), and the collision detection must be executed for (N 2 ) pairs. Taking into account that the interference between consecutive links does not occur since the movable range of the joints are limited, we still need to check (N 2 ) − (N − 1) pairs. This number of the combination becomes 350 in the case of HRP-1S whose N = 29. The average computation time for the collision detection is about 10 [ms], when HRP-1S takes many random posture. Here, the geometric model of HRP-1S consists of about 10,000 polygons. This is not fast enough, because the cycle of the controller is 5 [ms] and we assume that its 20% can be assigned for the collision inspection. From the above experiment, about 35 pairs can be checked in 1 [ms]. Then we propose the following approach combining an off-line pre-processing and a reduced on-line computation.
Figure 10: Safe posture for walking imental result is shown in Fig.11. The required time is longest when the robot is standing, and decreases while walking.
0.7
Processing Time[ms] Height of Left Foot[m] Height of Right Foot[m]
0.6 0.5 0.4 0.3 0.2
1. Check the self-collision at a rough resolution for each joint, and try to find safe range for some joint. 2. Re-check the self-collision at a fine resolution for the same range found at the previous step.
0.1 0
1
2
3
4
5
6[s]
Figure 11: Computation time for the self-collision while walking
6
Simulations and experiments
The modules which have been implemented on OpenHRP include (1) feedback controller for biped locomotion, (2) balance controller at the standing position, (3) collision avoidance planner for arm motions. (1) tries to stabilize the biped locomotion of the robot whose desired trajectories has been generated by an off-line pattern generator[9]. (2) keeps the balance of the robot which is supposed to carry out some task at the standing position[11]. (3) plans collision avoidance motions of an arm of the robot[11]. The dynamics simulation and the corresponding experiments are carried out to examine the proposed algorithms. The first example is a damped oscillation of the robot. The robot is inclined slightly at the standing position, and the external force to incline the robot is removed. Then the robot shows a damped oscillation along the pitch axis, when no feedback control is applied. Figure 12 shows the torque along the pitch axis of a foot of the robot. The curve with the higher
Figure 13: Normal repulsive force from the floor
Figure 14: Normal repulsive force by a rigid object model
based on a rigid object model. It is very difficult to evaluate feedback laws on such a simulation. This is one of the major feature of the proposed algorithm. Figure 15 shows a snapshot while the robot is walking on a rough terrain.
Figure 12: Damped oscillation of HRP-1S first peak is the result of the simulation, and the other is that of the experiment. The cycle of the oscillation and the attenuation rate seems to coincide sufficiently. The curves converge to slightly different values, which is caused by the calibration error to find the posture of the robot with the zero inclination. The next example is the comparison of the normal repulsive force from the floor to a foot of the robot while it is walking with a feedback control. The above curve is from the simulation and the below is from the experiment. The curves also seem to coincide sufficiently. Figure 14 shows the corresponding curve when the repulsive force is found based on the conservative law of momentum by V-HRP[11]. The robot seems to oscillate at a high frequency, since the simulation is
Figure 15: Walking on a rough terrain
The proposed geometric algorithm makes possible to execute such a simulation.
7
Conclusions
This paper presented an open architecture humanoid robot platform OpenHRP. The results can be summarized as follows. • The unification of the controllers for the virtual and real robot has been realized by introducing the adapters for two robots respectively with the synchronization mechanism, and employing ARTLinux on which real-time processing is available at the user level. • The consistency between the simulator and the robot is enhanced by the new algorithm to simulate general spring-damper mechanism. • Thanks to the unification, the controllers can share softwares with the dynamics simulator including the parameter parser, kinematics and dynamics computations and the collision detector. This feature can make the development of the controllers more efficient and the developed controllers more reliable. A realtime collision checker for humanoid robots has been developed as an example of the shared code. We claim that a humanoid robot platform deserves to be call a platform if the identical software can be used either on the simulator or on the robot and if the consistency between them is satisfactory kept. We believe that OpenHRP is expected to be the first humanoid robot platform in this sense and that it can initiate the exploration of humanoid robotics on an open architecture hardware and software.
Acknowledgments This research was supported by the Humanoid Robotics Project of the Ministry of Economy, Trade and Industry. The authors thank Hirochika Inoue, Yoshihiko Nakamura and Katsu Yamane from the University of Tokyo, and Kazuhito Yokoi, Kenji Kaneko and Kiyoshi Fujiwara from AIST for their cooperations.
References
[2] H.Hirukawa, T.Matsui and K.Takase, Automatic determination of possible velocity and applicable force of frictionless objects in contact from a geometric model, IEEE Trans. Robotics and Automation, pp.309-322, 1994. [3] K.H.Hunt and F.R.E.Crossley, Coefficient of Restitution Interpreted as Damping in Vibroimpact, ASME Journal of Applied Mechanics, pp.440-445, 1975. [4] H.Inoue, S.Tachi, K.Tanie, K.Yokoi, S.Hirai, H.Hirukawa, K.Hirai, S.Nakayama, K.Sawada, T.Nishiyama, O.Miki, T.Itoko, H.Inaba, and M.Sudo, HRP:Humanoid Robotics Project of MITI, In Proc. of the First IEEE-RAS International Conference on Humanoid Robots, 2000. [5] H.Inoue, S.Tachi, Y.Nakamura, K.Hirai, N.Ohyu, S.Hirai, K.Tanie, K.Yokoi and H.Hirukawa, Overview of Humanoid Robotics Project of METI, Proc. of the 32nd ISR, April, 2001. [6] Y.Ishiwata and T.Matsui, Development of Linux which has Advanced Real-Time Processing Function, In Proc. 16th Annual Conference of Robotics Society of Japan, pp. 355–356, 1998. [7] D.W.Marhefka and D.E.Orin, Simulation of Contact Using a Nonlinear Dampling Model, In Proc. IEEE Int. Conf. Robotics and Automation, pp.1662–1668, 1996. [8] Y.Nakamura, K.Yamane, H.Hirukawa and F.Nagashima, Distributed Computation Environments that Accelarate Humanoid Robotics Research and Applications, Preprints of ISRR, 1999. [9] Y.Nemoto, S.Hattori, T.Hagiwara, Y.Ichige, M.G.Fujie and A.Takanishi, Development of a Basic Motion Control Library for Humanoid, Proc. 32nd ISR, April, 2000. [10] M.S.Ohwovoriole and B.Roth, An Extension of Screw Theory, Trans. ASME J. Mechanical Design, vol.103, pp.725735, 1981. [11] Y.Nakamura, H.Hirukawa, K.Yamane, S.Kajita, K.Yokoi, K.Tanie, M.G.Fujie, A.Takanishi, K.Fujiwara, F.Kanehiro, T.Suehiro, N.Kita, Y.Kita, S.Hirai, F.Nagashima, Y.Murase, M.Inaba, and H.Inoue, V-HRP:Virtual Humanoid Robot Platform, In Proc. of the First IEEE-RAS International Conference on Humanoid Robots, 2000. [12] Y.Nakamura, H.Hirukawa, K.Yamane, S.Kajita, K.Fujiwara, F.Kanehiro, F.Nagashima, Y.Murase, and M.Inaba, Humanoid Robot Simulator for the METI HRP Project, In Proc. of the 32nd ISR, April, 2001. [13] F.Kanehiro, M.Inaba, H.Inoue, H.Hirukawa, and S.Hirai, Developmental Software Environment that is applicable to Small-size Humanoids and Life-size Humanoids, In Proc. of the 2001 IEEE International Conference on Robotics & Automation, 2001. [14] F.Kanehiro et al., Virtual Humanoid Platform to Develop Controllers of Real Humanoid Robots without Porting, In Proc. of the 2001 IEEE IROS, 2001. [15] K.Yamane and Y.Nakamura. Dynamics computation of structure-varying kinematic chains for motion synthesis of humanoid, In Proc. of the 1999 IEEE International Conference on Robotics & Automation, pp. 714–721, 1999. [16] http://www.omg.org/, Object Management Group.
[1] S. Gottschalk, M. C. Lin, and D. Manocha, OBB-Tree:A Hierarchical Structure for Rapid Interference Detection, In Proc. of ACM Siggraph ’96, 1996.
[17] http://luz.cs.nmt.edu/˜rtlinux, and M.Barabanov.
RT-Linux, V. Yodaiken