moves together with the trunk of the robot (see Fig. 9). The control area of each leg overlaps ones of the fore and/or rear legs. Therefore, the control area As i of ...
To appear in ICROS-SICE International Joint Conference 2009 August 18-21, 2009, Fukuoka International Congress Center, Japan. pp. 2247-2253, 2009.
Locomotion Control of Multi-Legged Robot based on Follow-the-Contact-Point Gait Tomoya Niwa1 , Shinkichi Inagaki1 and Tatsuya Suzuki1 1 Department
of Mechanical Science and Engineering, Nagoya University, Nagoya, Japan Tel : +81-052-789-2779; E-mail: {inagaki, t niwa}@nuem.nagoya-u.ac.jp
Abstract: This paper proposes a new control scheme of decentralized multi-legged robot based on Follow-the-ContactPoint (FCP) gait control. In this control scheme, the first legs contact the points allocated on the terrain and the following legs touch the foot on the point which the fore leg is contacting. By creating adequate contacting points on the environment, the robot can be navigated successfully. Since the position information of the contacting points is relayed based on physical information of the legs, each leg does not need the global position of the contacting point. As a result, the proposed control scheme realizes decentralized architecture. This paper introduces the control law for the robot walking on even terrain. Finally, the result of physical simulation of 20-legged robot shows the availability of the proposed method. Keywords: Multi-legged robot, Gait control, Decentralized control, Event-driven control, Mealy automaton
1. INTRODUCTION Multi-legged robots, like Fig.1, are desired to achieve high locomotivity. Since the multi-legged robots have many degrees of freedom, some decentralized architecture is required for the gait control. Many researchers address on decentralized gait control of multi-legged robot based on biologically inspired control, such as central pattern generators[1-3] and Walknet [4]. However, biologically inspired control has less compatibility between high-order processing, for example contact point planning, and the biological models. Based on this background, we propose a novel gait control scheme for multi-legged robots based on eventbased control, “Follow-the-Contact-Point” (FCP) gait control. FCP gait control is inspired from “Follow-TheLeader” (FTL) gait control [5] which is based on strategy that all legs follow the same planned contact point. The FTL gait is possible to realize gait control and navigation control simultaneously, but it is based on centralized control manner and has a drawback of slow-moving. It is because, while transferring the legs to the next contact points, the body has to stop the propulsion in order not to change the relative coordinate between the contact point and the body. This drawback stands out when the
Fig. 1 Conceptual illustration of multi-legged robot
number of legs is large like Fig.1. On the other hand, since the FCP gait is realized by relaying the contact points between the neighboring legs directly, the robot can move the legs without stopping the body. Furthermore, the FCP gait control is realized by decentralized control manner representing the same benefit as FTL gait control. This paper explains the algorithm of FCP gait control and shows the validity by showing simulation results of a multi-legged robot walking on level terrain. This paper is organized as follows: Section 2 introduces a multi-legged robot composed of N-segments and the control area of each segment. Sections 3 and 4 cover control modes of each leg and transitions of the control modes based on the leg state. Section 5 explains two methods to control moving direction of the robot. Section 6 reviews simulation results verifying the feasibility of our proposal. Section 7 discusses about characteristic of FCP gait control and section 8 presents conclusions.
2. DEFINITION OF CONTROL AREA First of all, we consider an N-legged robot (N ≥ 6) which is composed of homogeneous segments as shown in Fig.2. A segment is consist of a trunk and two legs, and the leg is composed of three links (coxa, tibia, and femur). Left (l) and right (r) legs of segment i ∈ {1, · · · , N} have coordinate systems Cis = (xis , ysi , zsi ), s ∈ {l, r}, and
Fig. 2 Segment and control area
Fig. 3 Phase of leg motion and control mode
the origin is assigned to the beginning point of each leg (coxa). Neighboring two trunks are connected by a revolute passive joint whose rotational axis is same as zsi axis. Each leg has a movable area Mis in which the leg tip can reach any point. We define a control area Asi ⊂ Mis in which the leg tip is permitted to contact the terrain. Since we address on the walk control on level terrain in this paper, we define Asi as a rectangular plane whose lengths are Lx and Ly respectively. In this control area, the leg tip can touch the terrain in the area of [− L2x , L2x ] in x-axis direction and [0, Ly ] in y-axis direction. The control area moves together with the trunk of the robot (see Fig. 9). The control area of each leg overlaps ones of the fore and/or rear legs. Therefore, the control area Asi of the leg i is divided to the following three or two areas: Area 1: Area overlapping Asi−1 . Area 2: Area without overlap. Area 3: Area overlapping Asi+1 . Note that the first and end legs do not have Area 1 and Area 3, respectively. Hereinafter, we omit upper suffix s ∈ {r, l} of variables, if not otherwise specified, because the left side legs and the right side legs are controlled independently.
3. LEG CONTROL Leg motion is composed of two phases, swing phase, and stance phase. In swing phase, the leg tip leaves the ground and approaches to the next contact point. In stance phase, the leg tip keeps contact with the ground and makes a propulsive force. Control in both phases is based on PD control as follows:
τm = Kp (θˆm − θm ) − Kd θ˙m
(1)
where τm is torque of motor m ∈ {1, 2, 3}, θm angle of motor m, θˆm the desired angle of motor m which is calculated from inverse kinematics of desired position of the leg tip, K p (> 0) and Kd (> 0) the proportional gain and the differential gain respectively. This kind of position control is easily realized by common servo motors. Leg control is composed of 4 modes, three swing phase control modes and one stance phase control mode (Fig.3). This section explains each control mode.
Fig. 4 Leg in swing phase: The leg tip stays at the midair point Pup , and approaches the next contact point.
3.1 Control Mode 1: Swing Phase 1 (Leaving Contact Point) In the swing phase 1, the leg tip leaves the contact point Pi and moves to a midair point Pup in the coordinate system Ci . The midair point Pup is allocated above the control area, Pup = (Xup ,Yup , −Zup ) in the left leg and Pup = (−Xup ,Yup , −Zup ) in the right leg. In this phase, the desired motor angle θˆm of (1) is calculated from inverse kinematics of Pup . 3.2 Control Mode 2: Swing Phase 2 (Staying at Midair Point Pup ) In the swing phase 2, the leg tip stays at the midair point Pup . This control is being activated until the fore leg tip i − 1 enters into Area 1 of leg i (see section 4 for details). In addition, the desired motor angle θˆm of (1) is calculated from inverse kinematics of Pup in this phase. 3.3 Control Mode 3: Swing Phase 3 (Approaching to Next Contact Point) In the swing phase 3, the leg tip leaves the midair point Pup and approaches to the next contact point Pnew (Fig.4). The position of the next contact point Pnewi , except for the first legs (i = 1), is calculated based on the contact point of the fore leg Pi−1 in the left leg:
xnewi ynew i znewi
=
cφi sφi 0
−sφi cφi 0
0 0 1
xi−1 − 2R + L yi−1 +W zi−1
+
L −W 0
(2) and in the right leg;
xnewi ynew i znewi
=
cφi sφi 0
−sφi cφi 0
0 0 1
xi−1 + 2R − L yi−1 +W zi−1
+
−L −W 0
(3)
Fig. 5 Leg in stance phase: The leg tip Pi moves toward the target point Ptarget with contacting the ground.
where Pnewi = (xnewi , ynew i , znewi )T and Pi−1 = (xi−1 , yi−1 , zi−1 )T , cφ = cos φ and sφ = sin φ , φi is the joint angle between trunks i − 1 and i, 2W , L and R are width of the trunk, length between the joint center and the trunk center, and radius of leg tip, respectively. The next contact point of the first leg Pnew1 is given by searching environment or by an operator directly. The timing to leave the leg tip from Pup is determined based on position of the fore leg tip (i ≥ 2) or position of the produced next contact point Pnew1 (i = 1) (see section 4 for details). In this phase, θˆm of (1) is calculated from inverse kinematics of the next contact point Pnewi . 3.4 Control Mode 4: Stance Phase Once the leg i contacts the next contact point Pnewi , the desired contact point Pˆi at each time instant is calculated as follows: (Ptarget − Pi ) Δi Pˆi = Pi + Ptarget − Pi
(4)
where Δi is propulsion distance of the desired contact point, Ptarget is the target point, |PA −PB | means the length between points PA and PB (Fig.5). Coordinate of the target point is (−Lx /2, Ytgt , −Lz ) in the left leg and (Lx /2, Ytgt , −Lz ) in the right leg. The propulsion distance Δi adjusts velocity of the leg tip and inherits one of the fore leg Δi−1 when the leg i contacts the contact point Pnewi . The timing of the leg tip leaving from the contact point is determined based on the rear leg condition except for the last segment (see section 4 for details). As for the end segment, the leg tip leaves the contact point when it crosses End line which is ruled at x = Xend in the left leg and at x = −Xend in the right leg, respectively. In this phase, θˆm of (1) is calculated from inverse kinematics of Pˆi .
4. CONTROL MODE TRANSITION Follow-the-Contact-Point (FCP) gait control is represented by Mealy automata (Figs.6, 7, 8 in the next page). Mealy automaton can represent reactive systems which produce output events according to an input event. The state transition is described as follows: inEvent[guard]/outEvent; · · · ; outEvent
(5)
where “inEvent” is an input event and “guard” is a guard condition. The mode transition fires and output events “outEvent” are produced simultaneously when inEvent
occurs and the guard condition is true. When the inEvent is omitted, the transition can fire anytime. State of FCP gait control automata corresponds to each phase described in section 3. Since the first (i = 1) and end (i = N) segments have no fore and rear neighbor segment respectively, the automata are different from one of middle segments. The following sections explain about each automaton. Note that the automata need to send/receive information to/from neighbor segments. We assume that the segment is able to communicate with the neighbors with no delay. In addition, the state transition is able to to occur at every control sampling instant. 4.1 Automaton of Middle Leg In Fig.6, the state 1 corresponds to the swing phase 1 of leg i, in which the leg tip is approaching the midair point Pup by the control of section 3.1. When the leg tip reaches the midair point Pup , the state changes to the state 2. In the state 2, the leg is controlled so as to stay the leg tip at the midair point Pup by the control of section 3.2. Also, in this state, the leg gets coordinate of the fore leg tip Pi−1 to calculate its relative position from the coordinate system Ci s , which is represented as “Get(Pi−1 )” in Fig.6. When the fore leg tip i − 1 enters Area 1 of leg i, the state changes to the state 3. In the state 3, the leg gets coordinate of the fore leg tip Pi−1 and calculates the new contact point Pnewi based on (2) or (3), which is represented as “Update(Pnewi )” in the figure. The leg is controlled by the control of section 3.3 so that the leg tip approaches the new contact point Pnewi . When the leg tip contacts the new contact point Pnewi , the leg i takes the propulsion distance of desired contact point Δi−1 from the fore leg and sends a message, “The leg tip contacted the terrain,” to the fore leg i − 1. In the state 4, the desired position of the leg tip Pˆi is calculated based on (4) at every control sampling instant and the leg tip is controlled to follow the desired point. When the leg receives a message about contact from the rear leg i + 1, the state changes to 1. Figure 9 shows the moving control areas and the mode changes of two legs. The control areas move according to the robot moving, but the contact point does not change except for little deviance which is due to the size of leg tip. FCP gait is achieved by propagating the contact points from the first leg to the end leg. Note that FCP gait control is perfectly decentralized since each segment only needs neighbor information: • Coordinate of the fore leg tip Pi−1 • Propulsion distance of desired contact point Δi−1 • Message about contact of the rear leg i + 1. 4.2 Automaton of First and End Leg Since the first segment (i = 1) has no fore segment, it has to make a new contact point Pnew1 by itself. A new contact point Pnew1 is produced when the leg tip leaves the contact point P1 . Position of a new contact point Pnew1 depends on moving direction of the robot. The method to produce a new contact point is described in section 5.
Fig. 6 Automaton of middle leg (i = 1, N) in FCP gait control
Fig. 7 Automaton of first leg (i = 1) in FCP gait control
Fig. 8 Automaton of end leg (i = N) in FCP gait control On the other hand, since the end segment (i = N) has no rear leg, it has to decide the timing when the leg tip leaves the contact point PN . The leg tip leaves the contact point when the leg tip crosses the end line (Fig.5).
5. CONTROL OF MOVING DIRECTION The moving direction of the robot can be changed by adding rotational torque to the segments. This section explains about two ways of moving direction control.
5.1 Allocation of New Contact Point of First Leg The moving direction of the robot is controllable by setting a next contact point of the first legs Pnew1 appropriately. In this paper, an operator gives a next contact point Pnew1 directly. A new contact point is allocated according to the desired moving direction (Fig.10). When moving forward, a new contact point is allocated on the same line of the target point Ptarget with some distance ahead from the front edge of the control area. As the result, the new contact point arrives at opportune position for the leg tip to contact. When turning left (right), a new contact point is allo-
Fig. 11 Multi-legged robot in simulation environment
Fig. 9 Moving control area and mode transition
Fig. 12 One segment of multi-legged robot
Fig. 10 New contact point of first leg cated on the left (right) side of the control area. Stride length of the opposite side legs against the turning direction is larger than one of the same side legs. That is why a new contact point which is far from the trunk is allocated closer to the control area. If the leg tip goes across the rear edge of the control area, the algorithm of FCP gait control falls in deadlock. Therefore, a new contact point has to be selected carefully so as to avoid deadlock. 5.2 Adjustment of Stroke Speed The segment can get rotational torque by different stroke speed between the left and right legs. When the left leg is faster (slower) than the right leg, the segment rotate to right (left). The stroke speed in stance phase is
adjustable by changing the propulsion distance of the desired contact point Δi . Since Δi is inherited from the fore leg i − 1, the moving direction of the robot can be controlled simply by changing the propulsion distance of the desired contact point Δ1 of the first legs. In actual control of moving direction, combination of the new contact point allocation and the stroke speed adjustment shows good turning performance.
6. SIMULATION We used three dimensional physical simulator PhysX [6] to verify our proposed gait control, FPC gait control. PhysX can simulate dynamics of large-scale systems in real time. We combined rigid bodies, joints, and motors to construct a 20-legged robot, 10 segments, in the simulation environment. FCP gait control was implemented in the robot. The sampling time of the gait control was 10 [ms] and one of dynamics calculation was 1 [ms]. The gravity acceleration was 9.81[m/s2 ]. 6.1 Robot Configuration and Parameters Figures 11 and 12 show the multi-legged robot which is constructed in the simulation environment. The com-
Fig. 14 Turning performance
Fig. 13 Gait diagram: Left side legs of 20 legged robot
ponent dimensions of the segment are shown in Table 1. Parameters used in FCP gait control are derived empirically (Table 2). In initial state, the control mode of each leg was set to 4 and the coordinate of each leg tip was (0, Ytgt , Lz ). 6.2 Simulation Result Figure 13 is gait diagram of the left side legs in the case of walking straight. The walking speed was about 0.5 [m/s]. This shows that periodic gait motion is successfully generated. In this figure, data was collected after 10 steps from the initial time because the algorithm of FCP gait control needed the steps to be stable. The new contact point which is created by the first leg needs 10 steps until it goes through the end leg. Figure 14 shows turning performance of the robot. The plotted points are contact points of the first legs. In this experiment, we combined two methods of moving direction control; the new contact point allocation (section 5.1) and the stroke speed adjustment (section 5.2). We comTable 1 Dimensions of segment component Trunk Link 1 Link 2 Link 3 Leg tip
Size (w×d×h) [m] 0.60 × 0.20 × 0.05 0.2 × 0.04 × 0.04 0.2 × 0.04 × 0.04 0.3 × 0.04 × 0.04 Radius [m]= 0.035
Mass [kg] 3.0 0.9 0.9 1.3 0.1
Table 2 Parameters N Lx Xup W Ytgt Xfr
10 0.6 [m] 0.1 [m] 0.15 [m] 0.375 [m] 0.5 [m]
Kp Ly Yup L Xend Yin
300 [N] 0.5 [m] 0.35 [m] 0.175 [m] 0.2[m] 0.35 [m]
Kd Lz Zup R
10 [Ns] 0.22 [m] 0.1 [m] 0.035 [m]
Yout
0.3 [m]
Fig. 15 Operation performance
pared 4 types of stroke speed combination in which “x1” means the propulsion distance of the desired contact point Δ1 is 0.02 [m], “x2” 0.04 [m], “x3” 0.06 [m], and “x1/2” 0.01 [m]. The combination of the right (x3) and the left (x1) shows the least turning radius, but the leg tips slipped too much. As a result, the combination of the right (x2) and the left (x1/2) is found to be optimal from the viewpoint of turning radius and slipperiness of the leg tips. We also examined operation performance (Fig.15). In order to control the moving direction, we used the combination of the new contact point allocation and the stroke speed adjustment, the right (x2) and the left (x1/2). An operator gave three commands, “walk straight,” “turn left,” and “turn right.” The plotted points are contact points of the first legs. This result shows that the FCP gait control has good operation performance on a level terrain. In this experiment, the both side legs sometimes synchronized because left and right legs are controlled independently, but the robot never tumbled thanks to a lot of contacts point. However, when the number of legs was 6, the robot did not tumble but sometimes lost stability because of the synchronization of the first legs. When the number of legs is small, some strategy to avoid the leg synchronization is needed.
7. DISCUSSION 7.1 Difference from CPG Models The FCP gait control is greatly different from conventional Central Pattern Generator (CPG) models. CPG models are basically focused on phase difference between legs’ motion. In contrast, the FCP gait control is focused on transference of physical information (phenomena) about legs’ contacting. This conceptual changeover makes simultaneous gait control and navigation control possible in decentralized manner. However, the FCP gait control is not autonomous decentralized control but only decentralized control because the legs are controlled merely based on events. Autonomy in the local controller plays essential role on fault tolerance and adaptability for environmental changes. Autonomous architecture also will be required in the FCP gait control for fault tolerance and adaptability. 7.2 Difference from Real Centipedes Our aim of this research is not to reveal mechanism of real centipedes, but to realize a multi-legged robot which has high locomotivity. Therefor, we have no interest in finding a mechanism of the FCP gait control in the nerve system of centipedes. However, behavioral comparison between a real centipede and a multi-legged robot is significant for improving the control law of the robot. While walking, a centipede makes a traveling wave, from the head to the tail, in the motion of legs [7]. Although the direction of the traveling wave is different, the robot which is controlled by FCP gait control also makes a travelling wave in the legs’ motion (Fig.13). In addition, when observing a real centipede’s walk, we can find that the centipede always makes the leg tips contact at the same points at which the fore leg contacted. This control scheme resembles to the FCP gait control and is considered to have an advantage from the viewpoint of simplifying a problem in contact points selection because of the following reason: The next contact point of each leg, except for the first legs, is already confirmed to be possible to support the body by the fore legs. Therefore, selection problem of contact points only depends on whether the first legs can support the body or not. As the result, a centipede is able to walk simply by finding next contact points in the environment for the first legs. However, contact rule of centipedes is different from that of the FCP gait control. Although the robot controlled by FCP gait control always contacts one contact point by one leg, a centipede contacts one contact point by multiple legs. Contacting one point by multiple legs is considered to be effective for increasing walking speed, and for decreasing the burden for searching new contact points in the environment. 7.3 Initial Step Problem of FCP Gait Control In our experiments, FCP gait control needed as many steps as the segments until it works cyclically. This is because the new contact point which is created by the first leg needs the steps until it goes through the end leg.
Solving this initialization problem is important to control the start of walking. 7.4 Joint between Segments We employed a free joint to connect between segments. The freedom between segments seems to play important role on relaxing an internal force caused by changing the moving direction. As for change of the impedance of the free joint between segments, Aoi et al. [2] reported that strength of impedance affects the turning performance of the multi-legged robot which was controlled by a CPG model. In also the FCP gait control, analysis of the role of joint between segments will be needed to progress the turning performance.
8. CONCLUSION We proposed Follow-the-Contact-Point (FCP) gait control to control multi-legged robots walking on a level terrain. FCP gait control is decentralized and eventdriven control which can be represented by automata. We showed the validity by some simulation results using a physical simulator. Extension of FCP gait control to make multi-legged robots possible to walk on a uneven terrain, autonomous production method of new contact points of the first legs by searching the environment, and parameter optimization by using automaton verification, are our future works.
REFERENCES [1] T.Odashima, H.Yuasa, M.Ito: “The autonomous decentralized myriapod locomotion robot which is consist of homogeneous subsystems,” JRSJ, Vol.16, No.7, pp.81–88, 1998. [2] S.Aoi, H.Sasaki, and K.Tsuchiya, ”A multilegged modular robot that meanders: investigation of turning maneuvers using its inherent dynamic characteristics,” SIAM Journal on Applied Dynamical Systems, Vol.6, No.2, pp.348–377, 2007. [3] S.Inagaki, T.Suzuki, H.Yuasa, T.Arai: “Wave CPG model for autonomous decentralized multi-legged robot –gait generation and walking speed control–,” Robotics and Autonomous Systems, Vol.54, pp.118– 126, 2006. [4] H.Cruse, Th.Kindermann, M.Schumm, J.Dean, J.Schmitz: “Walknet–a biologically inspired network ti control six-legged walking–,” Neural Networks, 11, 1435-1447, 1998. [5] F.Ozguner, S.J.Tsai, R.B.McGhee: “An approach to the use of terrain-preview information in roughterrain locomotion by a hexapod machine,” The International Journal of Robotics Research, Vol.3, No.2, pp.134–146, 1984. [6] www.nvidia.com [7] B.D.Anderson, R.J.Full, T.Chen,“ Mechanics of locomotion in centipedes,” American Zoologist, Vol.30, No.4, p.135A, 1990.