New potential field method for rough terrain path planning using genetic algorithm for a 6-wheel rover

New potential field method for rough terrain path planning using genetic algorithm for a 6-wheel rover

Robotics and Autonomous Systems 72 (2015) 295–306 Contents lists available at ScienceDirect Robotics and Autonomous Systems journal homepage: www.el...

3MB Sizes 28 Downloads 79 Views

Robotics and Autonomous Systems 72 (2015) 295–306

Contents lists available at ScienceDirect

Robotics and Autonomous Systems journal homepage: www.elsevier.com/locate/robot

New potential field method for rough terrain path planning using genetic algorithm for a 6-wheel rover Rekha Raja ∗ , Ashish Dutta, K.S. Venkatesh Department of Mechanical Engineering, IIT Kanpur, Uttar Pradesh, 208016, India

highlights • • • • •

Proposed a new potential field method for rough terrain path planning for a rover. A gradient function is introduced in the conventional potential field method. The gradient function depends on the roll, pitch and yaw angles of the rover. Weights of potential field function are optimized by using GA. Results prove that the new method is superior to conventional potential field method.

article

info

Article history: Received 31 July 2013 Received in revised form 8 June 2015 Accepted 15 June 2015 Available online 25 June 2015 Keywords: Path planning Planetary rover Autonomous systems Rover kinematics Potential field Genetic algorithm

abstract Motion planning of rovers in rough terrains involves two parts of finding a safe path from an initial point to a goal point and also satisfying the path constraints (velocity, wheel torques, etc.) of the rover for traversing the path. In this paper, we propose a new motion planning algorithm on rough terrain for a 6 wheel rover with 10 DOF (degrees of freedom), by introducing a gradient function in the conventional potential field method. The new potential field function proposed consists of an attractive force, repulsive force, tangential force and a gradient force. The gradient force is a function of the roll, pitch and yaw angles of the rover at a particular location on the terrain. The roll, pitch and yaw angles are derived from the kinematic model of the rover. This additional force component ensures that the rover does not go over very high gradients and results in a safe path. Weights are assigned to the various components of the potential field function and the weights are optimized using genetic algorithms to get an optimal path that satisfies the path constraints via a cost function. The kinematic model of the rover is also derived that gives the wheel velocity ratio as it traverses different gradients. Quasi static force analysis ensures stability of the rover and prevents wheel slip. In order to compare different paths, four different objective functions are evaluated each considering energy, wheel slip, traction and length of the path. A comparison is also made between the conventional 2D potential field method and the newly proposed 3D potential field method. Simulation and experimental results show the usefulness of the new method for generating paths in rough terrains. © 2015 Elsevier B.V. All rights reserved.

1. Introduction Developing autonomous mobile robotic systems capable of exploring other planets and the Moon, is of great interest to researchers. This involves the design of new mobile platforms, terrain map generation, localization, motion planning, manipulation, etc. The development of new motion planning algorithms on rough



Corresponding author. Tel.: +91 8005385125. E-mail addresses: [email protected] (R. Raja), [email protected] (A. Dutta), [email protected] (K.S. Venkatesh). http://dx.doi.org/10.1016/j.robot.2015.06.002 0921-8890/© 2015 Elsevier B.V. All rights reserved.

terrains are aimed at enhancing the exploration capabilities of mobile robotic systems. The path-planning problem for a mobile robot operating on rough terrain with six wheels is far more complex than that of a differential-drive mobile robot operating on a flat terrain with three or four wheels. The path planning techniques proposed by earlier researchers for mobile robot operating on flat terrain may not be directly applicable on rough terrain as the terrain cannot be simply classified into obstacles and free path. Also, the mobile robot may be designed to go over rough surface without toppling over, and hence obstacle avoidance algorithms are not applicable. In the case of rough terrain the terrain gradients have to be considered inside the path planning algorithm to get the best paths.

296

R. Raja et al. / Robotics and Autonomous Systems 72 (2015) 295–306

Motion planning for a 10 DOF mobile rover in 3D terrain has significant differences with the traditional motion planning of mobile robots and arm manipulators. Mobile rovers have a large number of DOFs that makes their motion planning difficult due to the presence of complex kinematics of the rover, interaction with the terrain and 3D environment. This involves motion planning with differential constraints associated with the equation of motion (velocity, acceleration etc.). As is explained in [1] several researchers have solved this differential constrained problem in two parts by first performing the path/trajectory generation and then satisfying the path/trajectory constraints. As an example, a particular path may be optimal in terms of minimum distance traversed to reach a goal point but the path may not satisfy the mobile robots velocity and acceleration constraints. Hence, motion planning in 3D involves the two parts: (i) finding a safe path from one point to another avoiding obstacles and (ii) ensuring that the rover can actually traverse the path satisfying its own constraints of velocity, acceleration, energy, etc. Part (i) is performed by the new potential field function with an added gradient force and part (ii) is ensured by optimizing the weights of the potential field function by minimizing a cost function that considers different rover constraints. In this paper, we present a new potential field method for rough terrain path planning considering geometric and physical properties of the terrain and the rover. A new potential field algorithm is proposed that consists of an attractive force, repulsive force, tangential force and a gradient force. The attractive force is applied to the desired goal, the repulsive force to the obstacles (high un-traversable gradients), a tangential force to avoid traps (concave obstacles) and a gradient force. The gradient force is a function of the roll, pitch and yaw of the rover, that is derived using the kinematic model of the rover depending on its location on the terrain. Different weights are assigned to the four components of the potential field function and they are optimized using genetic algorithms. This ensures that the generated paths also satisfy the path constraints of the rover for successfully traversing the path. This paper is organized as follows. The review of the previous work is presented in Section 2. Section 3 describes the kinematic analysis of the rover. Section 4 describes the proposed rough terrain motion planning algorithm. Different objective functions are compared in Section 5 to get the best path. Section 6 presents the simulation results obtained by applying the proposed method on different terrains and Section 7 presents the experimental results. Section 8 presents the conclusions. 2. Related work Muir and Neumann [2] presented kinematic modelling of the rover for 2-dimensional terrain. They have developed matrix transformation algebra to derive the equations of motion of OMRs (Ordinary Mobile Robots). Tarokh et al. [3] describe a method for kinematic modelling of the rocky Mars rover. Tarokh and McDermott [4] proposed a methodology for developing a complete kinematics model of a general All-Terrain Rover (ATR) and its interaction with the terrain. Seegmiller and Kelly [5] presented a simple algorithmic method to construct 3D kinematic models for any WMR (Wheeled Mobile Robot) configuration. There exist many different path planning methods that work well for mobile robots in plane terrain. The cell decomposition methods [6–8] in which the configuration space is divided into smaller regions called cells, then a connectivity graph is constructed according to the adjacency relationships between the cells. This method provides a path but is suitable only for lower dimensional C-spaces. In general, cell-decomposition methods are computationally expensive and are not recommended to use for high dimensional configuration spaces [9]. There are various types

of roadmap methods, including visibility graph [10], Voronoi diagram [11] and the silhouette [9]. These guarantee in finding path but the approaches are suitable for planar terrain. Probabilistic Roadmap Method (PRM) [12,13] has proved to be successful in finding feasible paths. However, the two limitations of unnecessary collision checks and narrow passage problem raised the need for further research. An evolutionary algorithm [14–17], genetic algorithm [18,19], fuzzy logic [20] concepts have been shown to be effective for planar terrain but do not extend well to rough terrain. The artificial potential field method was first proposed by Khatib [21] for manipulators. Koren and Borenstein [22] described the virtual force field concept and identified the limitations of local minima, non-smooth movement, oscillations due to obstacles, oscillations in narrow passages. Later researchers proposed a new potential field to handle local minima [23–26]. An improved wall following method for escaping local minima in artificial potential field was proposed by Zhu, Zhang, and Song [27]. A new harmonic potential function is proposed by [28]. Jia and Wang [29] proposed a modified potential function to overcome the problem of goals non-reachable with obstacles nearby (GNRON). The new attractive function decreases the potential around goals evidently to eliminate the problem. Velagic et al. [30] proposed a modified potential field method with fuzzy logic to pull the robot out of the local minima and attention is paid to detect the robot’s trapped state and its avoidance. Yin and Yin [31] defined new attractive and repulsive potential function with respect to the relative position, velocity, and acceleration among the robot, the goal and the obstacles, to make the robot plan its motion not only with right positions, but also with suitable velocities. The exponential decrease of potential around the obstacle can cause the paths to be very close to obstacles, raising safety issues. To tackle this situation, a virtual obstacle concept for obstacle avoidance was proposed by Shehata and Schlattmann [32]. Shehata and Schlattmann [33] proposed a method to optimize the robot size factor and the multiplying factor of repulsive potential to maintain safety margin around the obstacles by the use of NSGA II. Li et al. [34] proposed a method of obstacle avoiding trajectory using potential grid method to avoid recursive U-shaped, unstructured, cluttered, and maze-like environment. All the methods described above are based on a binary representation of the terrain in which regions of the terrain are considered either occupied or free cells. Iagnemma et al. [35] presented an overview of physics-based rover and terrain modelling techniques. A rough terrain motion planning method is presented in [36] that considered range data and computes the path using A* algorithm based on user-defined performance index (terrain roughness, robot turning cost and path length). Tarokh [37] developed a hybrid intelligent path planning for articulated rover in rough terrain. The algorithm first takes images of the natural terrain, and then differentiated background from the rock by calculating the optimum threshold value from the histogram of natural terrain. In this case, the author has considered the terrain as obstacle or free space. A path planning method considering gradient calculation and the instability of attitude manoeuvres on rough terrain is proposed in [38]. 3. Rover kinematics The rocker-bogie type rover consists of six wheels, a central body, a diferential, and rocker and bogie links. The 6-wheel system was designed to ensure contact of all the six wheels with the ground even while moving on highly uneven terrains. Fig. 1(a) and (b) show schematic diagram of the front view and the side view of the rover with the dimension. The experimental rover on the terrain is depicted in Fig. 1(c). Each of the wheels has an independent driving motor to maximize the traction capability of the rover. It

R. Raja et al. / Robotics and Autonomous Systems 72 (2015) 295–306

b

a

297

c

Fig. 1. Diagram of dimensions of the rover (a) front view, (b) side view, and (c) the rover.

means that the rover is an all-wheel drive vehicle, i.e. torque is independently provided to each of the six wheels. Four of the corner wheels are independently steered wheels and the steering angles are denoted by ψ1 , ψ2 for the front wheels and ψ5 , ψ6 for the rear wheels. The rover central body which is free to rotate on a diferential link (D) having rockers on both of its sides. Each rocker has a bogie (B1 , B2 for left and right side respectively) pivoted at one end and a wheel mounted on the other. These wheels on the rocker are termed as the rear wheels (w heel 5, w heel 6 for left and right side respectively). Fig. 2 shows schematic diagram of the left side of the rocker-bogie. When rear wheels of the both sides are at different heights, one rocker goes up and the other goes down relative to the central position of the rocker. The rocker angle is denoted by ρ . The left and right side of the rocker angles are represented by, ρ1 = ρ and ρ2 = −ρ1 respectively. Both sides of the bogie are connected to the rocker, with an angle denoted by β1 for the left side and β2 for the right side of the rover body respectively, and both ends of the bogie have the front and middle wheels connected to it. Two non-steerable mid-wheels (w heel 3 and w heel 4) and two steerable front wheels (w heel 1 and w heel 2) are attached to the bogie joint. The maximum allowable gradient that the rover can safely climb is 35° and it can also move on a terrain with maximum of 35° sidewise slope. Hence, maximum instantaneous change in height the rover can go over is considered as the maximum allowable threshold height 0.075 m (which is half of the rover wheel diameter). As the rover moves at very slow speeds of 5 cm/s the dynamic effects are negligible and a quasi-static model can adequately describe its behaviour.

x

Fig. 2. 2D view of rocker–bogie rover with all important points.

3.1. Position kinematics of the rover The main objective of the position kinematics is to find the configuration of the rover at any particular point on the terrain. It is also required for velocity kinematic analysis for driving the wheels of the rover to follow a desired path. Thus the result of the position kinematics gives us coordinates of all the important points of the rover. Fig. 2 shows the left side view of the rocker–bogie on a flat ground with all important points. Where, A1 , A3 , A5 are the position of centre of the front (w heel 1), middle (w heel 2) and rear (w heel 3) wheels respectively and C1 , C3 , C5 are the positions of contact points with the terrain of the front, middle and rear wheels respectively. The position of the bogie joint and rocker joint are denoted by B1 and R1 . Let a coordinate frame Ci , i = 1, . . . , 6 is attached to each wheel’s contact point. The x axis of the contact frame is tangent to the terrain surface at that point, z axis is normal to the surface and y axis is in the lateral direction of the wheel. The contact angle δi is the angle between z axis of Ai and Ci shown in Fig. 3. On a flat surface, the contact angle is always zero, it means that the z axis of the contact-frame always coincide with the z axis of the wheel-axle frame, but these may become non-zero on uneven terrains. Let us assume that the first wheel contact position C1 is known with respect to the reference coordinate frame R of the

Fig. 3. Coordinate frame assignment to the wheel contact at terrain.

rover. The homogeneous transformation matrix from the wheel contact frame C1 to the axle frame A1 is given by cδ1  0 = −s δ 1 0



C

TA11

0 1 0 0

s δ1 0 cδ1 0

rsδ1 0  , rcδ1  1



(1)

where s and c denote the sine and cosine respectively and the wheel radius is denoted by r. The coordinate position of the axle of the w heel 3 has been found by taking the distance between axle of w heel 1 and wheel 3 as rA1 A3 which is always constant. A parallel line is assumed to the given path at distance r along the Z-direction of the coordinate system of the wheel contact point as shown in Fig. 2. A sphere at A1 , with radius of rA1 A3 then cuts the parallel line. Thus, the intersection point gives the position of the axle of the w heel 3. Let, the two extreme points of the line segment, where the sphere cuts the line be P1 (xP1 , yP1 , zP1 ) and P2 (xP2 , yP2 , zP2 ). Thus, the coordinate of the axle of the w heel 3 is A3 (xA3 , yA3 , zA3 ), calculated as A3 = P1 + (P2 − P1 )t3 ,

(2)

298

R. Raja et al. / Robotics and Autonomous Systems 72 (2015) 295–306

where t3 =



t1 , t2 ,



and t2 = −B −

if t1 ≥ 0 and t1 ≤ 1 ; t1 if t2 ≥ 0 and t2 ≤ 1









B2 − 4AC /2A

= −B +



B2 − 4AC /2A, A = (xP2 − xP1 )2 +(yP2 − yP1 )2 +

(zP2 − zP1 )2 , B = 2((xP2 − xP1 )(xP1 − xA3 ) + (y10 − yP1 )(yP1 − yA3 ) + (zP2 − zP1 )(zP1 − zA3 )), C = xA3 + y2A3 + zA23 + x2P1 + y2P1 + zP21 − 2(xA3 xP1 + yA3 yP1 + zA3 zP1 ) − rA21 A3 .

The transformation from A3 to C3 can be obtained by rotating

δ3 about the axle, then translating by the wheel radius r in the negative z-direction. The position of the contact frame is given by A

C3 = TC33 × A3 .

(3)

The coordinate of bogie B1 is calculated with respect to A1 using A the transformation matrix TB11 and the rocker coordinate frame B

R1 is calculated by the transformation matrix TR11 . Once the configuration of the entire bogie and R1 is found, the coordinate of axle of the w heel 5 is determined. The procedure of finding the coordinate of the axle A5 of w heel 5 is same as the w heel 3. Here the centre of the sphere is taken at point R1 and radius is rR1 A5 (distance between rocker R1 and axle A5 ). Then the coordinate of the contact frame C5 is calculated. Similarly the right side of the rover wheel contact positions are determined. 3.2. Wheel velocity ratios of the rover The main objective of velocity kinematics is to obtain the required angular velocity ω ratios between the various wheels in 3-dimensional space to drive the rover on a given path. The method requires coordinates of all the important points of the rover at any position on the terrain as an input. Linear velocities at different points of the rover are shown in Fig. 2. Wheel 1 and w heel 3 are connected to each other with the bogie link (A1 − B1 − A3 ). Since, the distance between the axle of w heel 1 and w heel 3 is constant, therefore the relative velocity between the axles of these two wheels is zero. This can be written as,

−−→ − − → −−→ v→ (4) A1 .rA1 A3 = vA3 .rA1 A3 , − → −→ −−→ where vA1 = ωA1 × rA1 C1 is the velocity of the point A1 . −−→ − → − vA3 = ω→ A3 × rA3 C3 is the velocity of the point A3 . − − → rA1 A3 is a vector along the line joining the two points A1 and A3 . For − → example, let p and q are two different points and r = (x − x )ˆi + pq

p

q

(yp − yq )ˆj + (zp − zq )kˆ is a vector along the line joining the two points. −→ Also, ωA1 = ωA1 s(β1 ± ψ1 )ˆi + ωA1 c(β1 ± ψ1 )ˆj + (0)kˆ is the angular velocity of w heel 1. − ˆ ˆ ˆ ω→ A3 = ωA3 s(β1 )i + ωA3 c(β1 )j + (0)k is the angular velocity of wheel 3. ˆi, ˆj, kˆ are unit vectors along x, y, z direction respectively. − −→ rA1 C1 = (xA1 − xC1 )ˆi + (yA1 − yC1 )ˆj + (zA1 − zC1 )kˆ is the radius vector of w heel 1. − −→ rA3 C3 = (xA3 − xC3 )ˆi + (yA3 − yC3 )ˆj + (zA3 − zC3 )kˆ is the radius vector of w heel 2. − → − → −−→ Substitution of the values of vA1 , vA3 , rA1 A3 in Eq. (4) and rearranging the terms result in Box I. The velocity of the rocker bogie joint is then calculated as it is required to get angular velocity of the w heel 5. Since, the bogie joint is also a part of link 1, we can express the velocity of the axles A1 and A3 in terms of the bogie joint B1 and the angular velocity of the bogie ωB1 . The expression for angular velocity ratio of bogie joint and axle of front wheel is determined by

4. Motion planning algorithm In case of rough terrain environments, the motion planning algorithm has to generate a safe path and also ensure that the path constraints are satisfied, so that the rover can traverse the path satisfying its own constrains of velocity, acceleration, energy requirement and safety (e.g. does not overturn, etc.). Hence motion planning involves finding a safe path from one point to another avoiding obstacles and ensuring that the rover can actually traverse the path. 4.1. Terrain mapping A structured light system is used to obtain information of the local terrain, in the form of terrain elevation Zterraini at each point (Xi , Yi ), i.e., as discrete data. A uniform B-spline surface is then generated from the terrain information to generate a terrain map. In order to discard regions with large gradients and with significant height changes the terrain is classified into good and bad regions by using a threshold factor for the entire terrain. Hence, a binary map is generated, which is composed of free and untraversable region. Then each un-traversable region is segmented and clustered. The un-traversable segments are clustered depending on the condition that any two segments belonging to two separate clusters can never be closer than the threshold distance (diameter of the rover plus 0.01 m) that permits the safe motion of the rover. This step is necessary for the path planning strategy adopted. The application of potential field method requires the characterization of un-traversable region for applying the repulsive forces. Hence the boundary of the un-traversable region has to be approximated. Thereby, the concept of alpha shape [Matlab] is used to meet the requirement. An alpha shape is obtained by moving a circle of a pre-set radius around the region and connecting the points on the region it touches tangentially. In this case, the radius of such a circle was set as (0.075 + 0.01) m, that is the radius of rover plus safety distance (0.01 m) and the rover cannot enter very small concave regions. This pre-processing of the terrain data helps in reducing the total region that the rover can traverse. 4.2. Path planning algorithm In the potential field method, the rover is repelled by repulsive forces and attracted by attractive forces. The rover moves in a direction that is the resultant of all the forces at that point on the terrain. In the conventional potential field function, we have added a gradient force, so that the rover navigates through the uneven terrain depending on the local gradients of the terrain. The logic for using this is that the robot will avoid very high gradients. The new potential field function is written in terms of attractive (Fatt ), repulsive (Frep ), tangential (Ftan ) and gradient (Fgrad ) force. The net force acting on the rover is given by Ftotal = w1 × Fatt + w2 × Frep + w3 × Ftan + w4 × Fgrad ,

[(c(β1 ± ψ1 )(zC1 − zA1 )) − (Ac(β1 )(zC3 − zA3 ))] ωB1 = ωA1 [c(β1 )((zA1 − zB1 )(zA3 − zB1 ))] = B (say).

ωA

Similarly, the expression for ω 5 can be determined by Eq. (7) in A1 Box II: Similarly, we can find velocity ratio ωA4 /ωA2 , ωA6 /ωA2 for the wheels on the right side of rover, where ωA2 , ωA4 , and ωA6 are the angular velocities of front (w heel 2), middle (w heel 4) and rear (w heel 6) wheel for the right side of the rover.

(6)

(8)

where w1 , w2 , w3 , w4 are the weight parameters for the attractive, repulsive, tangential and gradient force respectively.

R. Raja et al. / Robotics and Autonomous Systems 72 (2015) 295–306

[(c (β1 ± ψ1 )(zC1 +(s(β1 ± ψ1 )(zA1 ωA3 = [(c (β1 )(zC3 ωA1 +(s(β1 )(zA1

− zA1 )(xA1 − zA3 )(yC1 − zA3 )(xA1 − zA3 )(yC3

299

− xA3 )) − (s(β1 ± ψ1 )(zC1 − zA1 )(yA1 − yA3 )) − yA1 )) − (c (β1 ± ψ1 )(xC1 − xA1 )(zA1 − zA3 ))] − xA3 )) − (s(β1 )(zC3 − zA3 )(yA1 − yA3 )) − yA3 )) − (c (β1 )(xC3 − xA3 )(zA1 − zA3 ))]

= A (say).

(5) Box I.

[C (xA5 − xB1 ) + D (yA5 − yB1 ) + E (zA5 − zB1 )] ωA5 = [(c(β1 ± ψ5 )(zR1 − zA5 )(xR1 − xA5 )) − (s(β1 ± ψ5 )(zR1 − zA5 )(yR1 − yA5 )) ωA1 +(s(β1 ± ψ5 )(zA5 − zB1 )(yR1 − yA5 )) − (c(β1 ± ψ5 )(xR1 − xA5 )(zA5 − zB1 ))]

(7)

Box II.

• Attractive force: The attractive potential is denoted by Uatt (q) and the attractive force Fatt (q) is given by the negative gradient of the attractive potential as Fatt (q) = − ▽ Uatt (q) = [∂ Uatt (q)/∂ x ∂ Uatt (q)/∂ y]T ,

(9)

where attractive potential Uatt (q) = d(q, qgoal ) is the  shortest distance between rover and goal, and ▽Uatt (q) = − q − qgoal

  /d q, qgoal . The attractive potential force can be of fixed magnitude [39], quadratic [21] or super quadratic [14] function. The centre of the rover and the goal position in the workspace are denoted by q = [x y z ]T and qgoal = [qgx qgy qgz ]T respectively. Where, Fattx (q) = qgx − x /pm (q, qgoal ) is force in x direction, Fatty (q) = |qgy − y|/pm (q, qgoal ) is force in





y direction and pm (q, qgoal ) = qgoal − q is the Euclidean distance between the robot q and the goal qgoal in 3-dimension and m = 1 or 2. This converges linearly towards zero as the robot approaches the goal. • Repulsive force: The repulsive force is non-negative and the magnitude of the function should tend to infinity as the rover approaches the obstacles’ surface. The repulsive potential is denoted by Urep (q) and the repulsive force Frep (q) is given by the negative gradient of the repulsive potential as





Frep (q) = − ▽ Urep (q)

=

   1

Dq

 



[0 0 ]T ,

1

ρr



1 D2q

 ▽ Dq ,

if Dq ≤ ρr

(10)

if Dq > ρr

where ρr is a positive constant denoting the repulsive radius of influence of the obstacle. The above repulsive force function is similar to [40] except certain differences: – In [40] the robot is considered as a point where as here it is taken as a circle. – Since the rover is taken as a circle, the shortest distance between rover and obstacle is Dq = d(q, qun−tr v rs ) − qrad . Here qrad denotes radius of the rover and denotes the closest point on the obstacle surface from the rover centre. – Unlike in [40], all the calculated distances are in 3D. • Tangential force: A tangential force component is introduced to overcome the shortcomings of local minima present in the conventional potential field method. The tangential force guides the rover along the contours of the obstacle, towards the goal point. The combined effect of the tangential force and the attractive force tries to move the rover towards the intermediate sub-goal (the point on the obstacle closest to the goal). The tangential force acts from the multiple obstacles which are under the tangential radius of influence (ρt ). The effect of tangential force depends on the distance to the closest obstacle surface.

Fig. 4. Geometric representation of gradient calculation.

The tangential force is proposed as

   exp(Dq )cφz exp(Dq )sφz T , Ftan (q) = if Dq ≤ ρt and dreach > dfollowed  [0 0]T , else

(11)

where distance between the goal and robot is dreach = d(qgoal , q) and distance between the goal and un-traversable region is dfollowed = d(qgoal , qun−tr v rs ). The tangential force acts in the direction tangent to the obstacle vertex (closest point on the obstacle from the rover). Due to this force, the rover can escape the concave like obstacles, instead of getting trapped due to local minima. • Gradient force: The gradient force is added so that the rover can avoid very high gradient and passes over low gradients in the terrain. On flat terrain the robot goes straight towards the goal if no obstacle exists in its path. But in the case of rough terrain, due to the gradient effect, the robot will not move straight, even if there are no obstacles present. In that case, the application of gradient force may increase the length of the path, but, minimizes energy, power consumption, and wheel slip. The gradient force is calculated as follows: the front direction of the rover is divided into sectors at 30°, starting at 0° from the left end of the central axis and ending at 180° at the right end of the axis, as shown in Fig. 4. At the end of each sector (point where the radius meets the circumference) the gradient force acting on the rover is computed. We have assumed that the centre of the rover is above this point as it moves forward. Assuming one contact point between the wheel and terrain, the roll, pitch and yaw angles of the centre of the rover are found using the kinematic model. The gradient force is given by Fgrad (q) = [exp(grad)cφz exp(grad)sφz ]T ,



(12)

where grad = (∆φx + ∆φy ). The gradient force has been computed using only the roll and pitch angles of the centre of the

300

R. Raja et al. / Robotics and Autonomous Systems 72 (2015) 295–306

rover, assuming that the yaw angle is zero. This has been done as the yaw angle is the steering angle of the rover, and it depends on the sector angle on which the rover is. From the initial position of the rover on the terrain a semicircle is first drawn with a radius of ρg = 500 mm. This semicircle is then divided into sectors and the gradient force found for each sector. Next the radius of the circle is increased by 100 mm and the gradient force is again found for each sector. This is equivalent to the rover moving forward by 100 mm. This process is followed to cover the whole terrain. Algorithm 1 describes the developed new potential field method. Fig. 5. Force analysis between the wheels and the ground.

Algorithm 1 New Potential Field Algorithm Input: terrain map, start position, and goal position of the rover 1: Assign high potential value to Obstacles 2: Assign low potential value to the Goal 3: If obstacle is encountered go to 4 else go to 5 4: Compute attractive, repulsive, tangential, and gradient force to obtain resultant force Ftotal for a particular set of weights 5: Compute attractive, and gradient force to obtained resultant force Ftotal , where the magnitude of repulsive and tangential force is zero 6: Calculate (l + 1)th (next) position of the rover in the direction of resultant force 7: Check all the constraints at (l + 1)th position. If constraints are satisfied then go to Step 8 else consider that position as obstacle and go to Step 3. 8: Execute the movement of the rover 9: If robot reached the goal then go to Step 10 else go to Step 3 10: Stop

4.3. Motion constraints The constraints that need to be satisfied by the rover because of its structure and for motion on the terrain are explained next. (a) Wheel contacts: The rover must satisfy the kinematic constraints that the wheels must be in contact with the terrain at all times, while it traverses a path. The terrain geometry is taken as input to the analysis, and one contact angle between a wheel and surface is assumed. Then following the geometrical method explained earlier the other wheel contact points are found. (b) Stability analysis: In order to ensure rover safety during traversing on rough terrains, a quasi-static force analysis is performed at each configuration along the rover path to determine that the rover does not topple over. A three-dimensional force analysis yields the forces Fx , Fz , and moments My that are applied from the body to each rocker joint shown in Fig. 5. The force analysis is divided into two planar problems. Here δ1 , δ3 and δ5 are the inclination angles at corresponding wheel contact points with the ground. N1 , N3 , N5 are the normal forces, and T1 , T3 , T5 are the tangential friction forces for w heel 1, w heel 3, and w heel 5 respectively. The mathematical formulations of the equations involved in the analysis are similar to the equations obtained in [41]. The resulting static equilibrium equations are:



Fx = Fx − N1 sδ1 − N3 sδ3 − N5 sδ5

+ T1 cδ1 + T3 cδ3 + T5 cδ5 = 0 

(13)

Fz = Fz + N1 cδ1 + N3 cδ3 + N5 cδ5

+ T1 sδ1 + T3 sδ3 + T5 sδ5 = 0.

(14)

The moment about the point R1 and the bogie joint B1 are derived as follows:



FMy ,R1 = My + (x8 − x5 )N5 cδ5 + (x8 − x6 )T5 sδ5

+ (z8 − z5 )N5 sδ5 − (z8 − z5 )T5 cδ5 + (x8 − x3 )N1 cδ1 + (x8 − x3 )T3 sδ3 + (z8 − z6 )N3 sδ3 − (z8 − z3 )T3 cδ3 + (x8 − x1 )N1 cδ1 + (x8 − x1 )T1 sδ1 + (z8 − z1 )N1 sδ1 − (z8 − z1 )T1 cδ1 = 0 

(15)

FMy ,B1 = (x7 − x3 )N3 cδ3 + (x7 − x3 )T3 sδ3

+ (z7 − z3 )N3 sδ3 − (z7 − z3 )T3 cδ3 + (x7 − x1 )N1 cδ1 + (x7 − x1 )T1 sδ1 + (z7 − z1 )N1 sδ1 − (z7 − z1 )T1 cδ1 = 0.

(16)

The equations of the stability analysis consider various physical constraints, e.g., to ensure no loss of contact between the wheels and the terrain. The negative value of the normal force indicates the loss of contact between the wheels and the ground. There are six numbers of unknowns (T1 , T3 , T5 , N1 , N3 , N5 ) in the four Eqs. (13)–(16). Therefore, these equations are under-constrained and the solution is not unique. The above equations are solved as in [41] by parameterizing the traction forces and the solutions are then checked for the constraints described below: ∥Ti ∥ ≤ µ ∥Ni ∥, ensures no slip for ith wheel, Ni ≥ 0 ensures ith wheel ground contact, ∥τi ∥ ≤ τmax , ensures that ith wheel motor does not saturate, where µ is the friction co-efficient between wheel and ground, τi is the motor torque of ith wheel of the rover and it is related to the tangential force Ti by the wheel radius. τmax is the maximum allowable motor torque. (c) Joint limits: The kinematic constraints for the rover are given below: • Maximum steering angle ±45°. • Maximum body pitch ±20°. • Maximum body roll ±15°. • Maximum speed on flat terrain 10 cm/s. • Maximum speed on rough terrain 5 cm/s. • Curvature: The curvature of a path traversed by the rover at dϕ any point is the limiting ratio of dϕz and ds i.e., κ = dsz , where dϕz is the angle (in radians) between tangents at points Pi−1 (start of a segment of the path) and Pi (end of a segment of the path), and ds is the length of that segment. So, dϕ at point Pi , the curvature κ = dsz = (ϕzi − ϕzi−1 )/ds ≤ 0.5. 5. Comparing objective function to get best path 5.1. Objective functions Four different objective functions are evaluated considering velocity ratios of the rover wheel for minimum energy using Eq. (17), quasi-static force analysis for wheel slip using Eq. (18), power consumption using Eq. (19) and length of the path of the rover using Eq. (20).

R. Raja et al. / Robotics and Autonomous Systems 72 (2015) 295–306

f1 = min

s  l =1

       ωA 2  ωA 2   ωA 2  ωA 2 3 5 6 4  Ll ∗    + + ωA1 ωA1 ωA2 ωA2

301



(17)

where Ll is the length of the path between lth and (l + 1)th segments in the path, and s denotes the number of segments in the path. Box III.

(i) To ensure the minimum energy consumption of the rover while traversing a path a new objective function has been formulated using the ratio of wheel velocities as equation given in Box III. The objective of Eq. (17) is to minimize the energy by assuming that the energy of the rover is proportional to ω2 . When rover is on flat ground or all the six wheels are in same slope the velocity ratios of the wheels are equal to 1. When rover traverses towards the positive slope of the terrain the angular velocity ratios of the rover are greater than 1, and when it traverses towards negative slope of the terrain, the values of angular velocity ratios lie between (0,1). The effect of differential between both the sides of the rover comes into picture when both sides of the rover are in different heights. (ii) The CF for maximum traction at the wheel–ground interface is developed based on the general observation that for most soils the maximum traction force a soil can support increases with increasing normal force [42]. Thus, to avoid terrain failure and wheel slip, the algorithm should minimize the ratio of the traction force to the normal force along the path. Similar criteria has been developed in [43] and later used in [44]. f2 =

s 

max

l=1

i

Ti Ni

,

(18)

(iii) A criteria for minimum power consumption [45] of the vehicle is related to the tractive force Ti . The minimum power consumption along the path is given by f3 = min

n s  νσ 2 r 2  l =1

Kt2

Ti2

(19)

i =1

where n denotes the number of wheels of the rover (i = 1, . . . , n), ν is the motor resistance, Kt is the motor torque constant and σ is the gear ratio. (iv) The length of the path from the start to the goal position of the robot is determined by f4 = min

s  (Ll ),

(20)

l =1

where Ll =



 (xl+1 − xl )2 + (yl+1 − yl )2 + (zl+1 − zl )2 .

The four different paths found using the different objective functions are then compared to choose the desired path. 5.2. Optimum weight estimation using GA We have used Genetic Algorithm (GA) to optimize the weights of the potential field function by minimizing a CF subject to constraints. A large penalty parameter is added to the CF for those individual paths which are infeasible. The paths of the robot from the start to the goal depend on the weight factors w1 , w2 , w3 and w4 of the potential function. The fitness for each individual path is calculated using Eqs. (17)–(20). The values of GA parameters considered are:

• Minimum population size = 50, • Minimum number of generations = 300,

Fig. 6. Simulation result for terrain with un-traversable region.

• • • • •

Crossover rate = 0.9, Mutation rate = 0.1, Tolerate value = 1e − 3, Lower bound of population = [0, 0, 0, 0], Upper bound of population = [200, 200, 200, 200].

6. Simulation results A program was written in Matlab that takes input from the structured light system. The terrain on which paths are found in the simulations are real terrains on which the rover is later experimented with. Several simulation have been carried out with different types of terrain to illustrate the difference between the conventional potential field method (without gradient force) and the new method being proposed. First the conventional potential method is used by dividing the terrain into free space and obstacles, and the gradients are ignored. The results show that the rover passes over the high gradients and in between the un-traversable part to reach the goal. Fig. 6 shows the simulation result with un-traversable region on the terrain using the conventional potential field method. Here, the rover initially approaches a straight line path towards goal and when it encounters obstacles it avoids the obstacles and reaches the target position safely. Fig. 7 shows the simulation result with tangential force to avoid local minima and trap situation. In Fig. 7(a) the rover can move inside narrow passages without oscillating. In Fig. 7(b) which uses the tangential force the rover is able to avoid the trap situation and reach the goal position. Fig. 8(a) shows the simulation results using conventional and newly proposed potential field method for a terrain with no obstacles but with gradients. Fig. 8(b) shows the 3D representation of the same terrain. In this case, all the points of the terrain are traversable. Even if there is no obstacle in the workspace then also the rover does not go straight as the proposed method aims to minimize the energy (objective-1) of the path due to the effect

302

R. Raja et al. / Robotics and Autonomous Systems 72 (2015) 295–306

Fig. 7. (a) Overcoming oscillation and local minima, and (b) 2D representation for overcoming 3D trap situation.

Fig. 8. Simulation result for terrain with no un-traversable region: (a) 2D representation, and (b) 3D representation.

Fig. 9. Comparative result for different objective functions: (a) 2D representation, and (b) 3D representation. Table 1 Comparative results for motion planning algorithm for each objective function in Fig. 9. Function number

Function value

w1

w2

w3

w4

Objective-1 Objective-2 Objective-3 Objective-4

5.6793 61.7927 1.4726 5.3480

20.0 15.5 32.0 57.0

0.140 1.895 0.234 0.712

0.996 0.341 0.308 0.960

1.525 0.9143 1.862 1.781

of gradient force. But, by the conventional method the rover goes straight towards the goal from the start position. Simulation was done for each of the four objective functions in the terrain shown in Fig. 9 with the same start and goal using the proposed method. The obtained optimum paths and the weights of potential function are different depending on the objective function. The proposed approach provides the best path according to the objective function and the weights of the potential function are also optimal.

As shown in Table 1 the weight of the attractive potential varies from 15 to 57 while the weight of the repulsive potential is the least and varies from 0.1 to 1.8. It is found that the weight of the attractive potential is the highest, the gradient potential is the second highest, the tangential potential is the third highest and the weight of the repulsive potential is the least. This can be logically explained as the robot has to always move towards the goal position and hence this component of force has to be the highest. The gradient force is the second highest as it has to ensure that the robot does not go over very high gradients. The tangential force comes into effect only when the robot is within its range of influence and hence it is not always active. The repulsive force also acts only when the robot is very near to the obstacle and hence its influence is the least. This relative importance of the weights clearly shows the importance of adding the gradient force component in the potential field method. It also proves that 2D conventional potential field method (gradient force equal to zero) will not give optimal paths in the case of 3D terrain with gradients.

R. Raja et al. / Robotics and Autonomous Systems 72 (2015) 295–306

303

Fig. 10. Simulation result on uneven terrain: (a) 2D representation, and (b) 3D representation. Table 2 Comparative results between conventional and proposed algorithm for each objective function. Case No.

Method

obj1

obj2

obj3

obj4

Case-1

Conventional Proposed

4.1336 4.0443

97.4182 61.7927

4.5327 0.7145

4.1626 4.3710

Case-2

Conventional Proposed

5.3661 5.2616

1700.2 467.8126

17.9020 10.6363

4.9480 5.3207

Case-3

Conventional Proposed

5.8231 5.7764

951.142 810.8502

20.5217 18.8629

4.8359 5.1034

Case-4

Conventional Proposed

2.1336 1.863

27.4182 21.9786

0.9327 0.564

2.2598 2.015

Fig. 11. Comparative results between conventional method and proposed method.

The simulation result is presented in Fig. 10 considering another uneven terrain. It is clearly visible from the figure that the rover can easily traverse through the complicated environment where a big concave shape un-traversable region exists. Fig. 11 shows the simulation result with no obstacle (repulsive potential and tangential force equal to zero) in the uneven terrain. The rover follows the straight line path for conventional method. By the proposed method the rover follows a different path due to the gradient effect. It also shows the comparative results of simulation and experiment. Table 2 shows the comparative results between the conventional and proposed algorithm for each objective function. Case-1 is for the terrain shown in Fig. 8. Case-2 is for the terrain shown in Fig. 9. Case-3 is for terrain shown in Fig. 10. Case-4 is for terrain shown in Fig. 11. In Cases 1–3 the rover finds the minimum energy, and wheel slip of the path by the proposed method compared to the conventional potential field method. However it is to be noted that

the length of the path is higher in the case of the newly proposed method (Cases 1–3) even though the value of the objective function is lower. 7. Experimental results The rover was experimentally evaluated for following the optimal paths as found in the simulations on different terrains. The structured light scanning method was used to map the 3D terrain. The terrain was constructed using coarse sand and small rocks to produce different types of gradients and obstacles. The scanned terrain data was converted to grids of size 45 × 45 mm. The paths generated by the simulation using the new potential field method were then traversed by the rover. The rover is driven by ten motors (six drive motors Maxon EC MAX 30, 40 W, 12 V DC and four steering motors EC MAX 32, FLAT MOTOR, 15 W, 12 V

Fig. 12. The rover on the experiment terrain at different instances.

304

R. Raja et al. / Robotics and Autonomous Systems 72 (2015) 295–306

of the rover is then extracted from each frame of the video to get the path of the rover. The difference between the simulated path and the actual path is then analysed by computing the root mean square error (RMSE) and the average error, which are calculated as: RMSE

=



((xd (i) − xa (i))2 + (yd (i) − ya (i))2 + (zd (i) − za (i))2 ), (21)

where Pd = (xd , yd , zd ) are the coordinates of the desired simulated path and Pa = (xa , ya , za ) are the coordinates of the actual path obtained from the experiment and l is a number of points on the path. The average error of a path is defined by, Fig. 13. Comparative result between simulated and experimented path.

average error =

l 1

l i=1

|(Pa (i) − Pd (i))| .

(22)

For the path corresponding to Fig. 11 the experimental result is shown in Fig. 12. Length of the simulated path is 201.51 cm and the experimented path is 203.247 cm. The average error of the path is 0.697 cm and the RMS error of the path is shown in Fig. 13. Another experiment was carried out for the terrain shown in Fig. 14 and the rover on the experimental terrain at different instances are depicted in Fig. 15. The length of the simulated path is 532.07 cm and the experimented path is 527.37 cm. The average error between the simulated and experimented path is 0.934 cm and the RMS error is shown in Fig. 16. The error was due to the following reasons: Fig. 14. Comparative result between simulated and experimented path.

DC). Each motor has its own motor controller that is connected to a central PC. The simulations run on the PC and the optimal path is first generated. From the kinematic model as described earlier the wheel velocities for traversing the path are generated at different points along a desired path. The wheel velocities are then given to the motor controller for moving the rover on the path. Two colour markers are attached on the top of the rover. While the rover moves a camera is used to record the video of the motion. The position

• terrain is deformable. • wheels slips on the terrain and deviates from the desired path etc. 8. Conclusion This paper presents a new potential field method that incorporates the kinematics of a six wheel rover for motion on rough 3D terrain. The method avoids concave un-traversable area without getting trapped in it and it also eliminates oscillations and gives

Fig. 15. The rover on the experiment terrain at different instances.

R. Raja et al. / Robotics and Autonomous Systems 72 (2015) 295–306

305

[21] O. Khatib, Real-time obstacle avoidance for manipulators and mobile robots, Int. J. Robot. Res. 5 (1) (1986) 90–98. [22] Y. Koren, J. Borenstein, Potential field methods and their inherent limitations for mobile robot navigation, in: IEEE International Conference on Robotics and Automation, 1991, pp. 1398–1404. [23] J. Ren, K.A. McIsaac, R.V. Patel, Modified newton’s method applied to potential field-based navigation for mobile robots, IEEE Trans. Robot. 22 (2) (2006) 384–391. [24] B.-x. Xiao, L. YU, S.-s. LI, R.-b. CHEN, Research of escaping local minima strategy for artificial potential field, J. Syst. Simul. 19 (19) (2007) 4495–4503. [25] K. Al-Sultan, M. Aliyu, A new potential field-based algorithm for path planning, J. Intell. Robot. Syst. 17 (3) (1996) 265–282.

Fig. 16. Comparative result between simulated and experimented path.

smoothness in the path. Four different cost functions give the relative importance of the paths with respect to energy, traction force, slip and deviation from a straight line. The simulation and experimental results prove the effectiveness of the proposed method and also show the difference with the conventional 2D potential field method. It is proved by extensive simulations and experiments that the proposed method gives better paths as compared to the conventional potential field method. References [1] C. Goerzen, Z. Kong, B. Mettler, A survey of motion planning algorithms from the perspective of autonomous uav guidance, J. Intell. Robot. Syst. 57 (1–4) (2010) 65–100. [2] P.F. Muir, C.P. Neuman, Kinematic modeling of wheeled mobile robots, J. Robot. Syst. 4 (2) (1987) 281–340. [3] M. Tarokh, G. McDermott, S. Hayati, J. Hung, Kinematic modeling of a high mobility mars rover, in: IEEE International Conference on Robotics and Automation, vol. 2, 1999, pp. 992–998. [4] M. Tarokh, G.J. McDermott, Kinematics modeling and analyses of articulated rovers, IEEE Trans. Robot. 21 (4) (2005) 539–553. [5] N. Seegmiller, A. Kelly, Enhanced 3d kinematic modeling of wheeled mobile robots. [6] F. Avnaim, J.-D. Boissonnat, B. Faverjon, A practical exact motion planning algorithm for polygonal objects amidst polygonal obstacles, in: IEEE International Conference on Robotics and Automation, 1988, pp. 1656–1661. [7] J.-C. Latombe, Robot Motion Planning, Kluwer Academic Publishers, 1991, p. 25. [8] D. Zhu, J.-C. Latombe, New heuristic algorithms for efficient hierarchical path planning, IEEE Trans. Robot. Automat. 7 (1) (1991) 9–20. [9] J.-C. Latombe, Motion planning: A journey of robots, molecules, digital actors, and other artifacts, Int. J. Robot. Res. 18 (11) (1999) 1119–1128. [10] J.L. Guzmán, M. Berenguel, F. Rodríguez, S. Dormido, An interactive tool for mobile robot motion planning, Robot. Auton. Syst. 56 (5) (2008) 396–409. [11] S. Garrido, L. Moreno, D. Blanco, P. Jurewicz, Path planning for mobile robot navigation using voronoi diagram and fast marching, Int. J. Robot. Autom. 2 (1) (2011) 42–64. [12] L.E. Kavraki, P. Svestka, J.-C. Latombe, M.H. Overmars, Probabilistic roadmaps for path planning in high-dimensional configuration spaces, IEEE Trans. Robot. Automat. 12 (4) (1996) 566–580. [13] E. Kavraki, M.N. Kolountzakis, J.-C. Latombe, Analysis of probabilistic roadmaps for path planning, IEEE Trans. Robot. Automat. 14 (1) (1998) 166–171. [14] P. Khosla, R. Volpe, Superquadric artificial potentials for obstacle avoidance and approach, in: IEEE International Conference on Robotics and Automation, 1988, pp. 1778–1784. [15] S. Mittal, K. Deb, Three-dimensional offline path planning for uavs using multiobjective evolutionary algorithms, in: Proceedings of the Congress on Evolutionary Computation (CEC), Singapore, 2007, pp. 3195–3202. [16] P. Vadakkepat, K.C. Tan, W. Ming-Liang, Evolutionary artificial potential fields and their application in real time robot path planning, in: Proceedings of the Congress on Evolutionary Computation, vol. 1, IEEE, 2000, pp. 256–263. [17] J. Xiao, Z. Michalewicz, L. Zhang, K. Trojanowski, Adaptive evolutionary planner/navigator for mobile robots, IEEE Trans. Evol. Comput. 1 (1) (1997) 18–28. [18] H. Burchardt, R. Salomon, Implementation of path planning using genetic algorithms on mobile robots, in: IEEE Congress on Evolutionary Computation, 2006, pp. 1831–1836. [19] O. Castilho, L. Trujilo, Multiple objective optimization genetic algorithms for path planning in autonomous mobile robots, Int. J. Comput. Syst. Signal 6 (1) (2005) 48–63. [20] R. Raja, S.N. Shome, S. Nandy, R. Ray, Obstacle avoidance and navigation of autonomous mobile robot, Adv. Mater. Res. 403 (2012) 4633–4642.

[26] J. Lee, Y. Nam, S. Hong, W. Cho, New potential functions with random force algorithms using potential field method, J. Intell. Robot. Syst. 66 (3) (2012) 303–319. [27] Y. Zhu, T. Zhang, J. Song, An improved wall following method for escaping from local minimum in artificial potential field based path planning, in: Proceedings of the 48th IEEE Conference on Decision and Control, held jointly with the 28th Chinese Control Conference, CDC/CCC, 2009, pp. 6017–6022. [28] A.A. Masoud, A harmonic potential field approach with a probabilistic space descriptor for planning in non-divisible environments., in: IEEE International Conference on Robotics and Automation, ICRA, 2009, pp. 3774–3779. [29] Q. Jia, X. Wang, Path planning for mobile robots based on a modified potential model, in: International Conference on Mechatronics and Automation, ICMA, IEEE, 2009, pp. 4946–4951. [30] J. Velagic, B. Lacevic, N. Osmic, Efficient path planning algorithm for mobile robot navigation with a local minima problem solving, in: IEEE International Conference on Industrial Technology, ICIT, 2006, pp. 2325–2330. [31] L. Yin, Y. Yin, An improved potential field method for mobile robot path planning in dynamic environments, in: 7th World Congress on Intelligent Control and Automation, WCICA, IEEE, 2008, pp. 4847–4852. [32] H.H. Shehata, J. Schlattmann, Mobile robot path planning and obstacle avoidance based on a virtual obstacle concept, in: Proceedings of the 21 st International Conference on Flexible Automation and Intelligent Manufacturing, Taichung, Taiwan, vol. 2, 2011, pp. 905–914. [33] H.H. Shehata, J. Schlattmann, Potential field multi-objective optimization for robot path planning using genetic algorithm, CLAWAR, 2014. [34] C. Li, G. Cui, H. Lu, The design of an obstacle avoiding trajectory in unknown environment using potential fields, in: IEEE International Conference on Information and Automation, ICIA, 2010, pp. 2050–2054. [35] K. Iagnemma, H. Shibly, A. Rzepniewski, S. Dubowsky, Planning and control algorithms for enhanced rough-terrain rover mobility, in: International Symposium on Artificial Intelligence, Robotics, and Automation in Space, 2001. [36] K. Iagnemma, S. Kang, H. Shibly, S. Dubowsky, Online terrain parameter estimation for wheeled mobile robots with application to planetary rovers, IEEE Trans. Robot. 20 (5) (2004) 921–927. [37] M. Tarokh, Hybrid intelligent path planning for articulated rovers in rough terrain, Fuzzy Sets and Systems 159 (21) (2008) 2927–2937. [38] T. Ohki, K. Nagatani, K. Yoshida, Safety path planning for mobile robot on rough terrain considering instability of attitude maneuver, in: IEEE/SICE International Symposium on System Integration (SSI), 2010, pp. 55–60. [39] J. Borenstein, Y. Koren, Real-time obstacle avoidance for fast mobile robots, IEEE Trans. Syst. Man Cybern. 19 (5) (1989) 1179–1187. [40] S.S. Ge, Y.J. Cui, New potential functions for mobile robot path planning, IEEE Trans. Robot. Autom. 16 (5) (2000) 615–620. [41] S. Parakh, P. Wahi, A. Dutta, Velocity kinematics based control of rocker-bogie type planetary rover, in: TENCON IEEE Region Conference, 2010, pp. 939–944. [42] M.G. Bekker, Introduction to terrain-vehicle systems, 1969. [43] S. Sreenivasan, B. Wilcox, Stability and traction control of an actively actuated micro-rover, J. Robot. Syst. 11 (6) (1994) 487–502. [44] K. Iagnemma, S. Dubowsky, Mobile robot rough-terrain control (rtc) for planetary exploration, in: Proceedings of the 26th ASME Biennial Mechanisms and Robotics Conference, DETC, 2000, pp. 10–13. [45] S. Dubowsky, C. Moore, C. Sunada, On the design and task planning of power efficient field robotic systems, in: Proceedings of the ANS 6th Topical Meeting on Robotics and Remote Systems, 1995, pp. 501–508.

Rekha Raja obtained her Bachelor’s degree from the Jalpaiguri Govt. Engineering College, West Bengal University of Technology, India, in 2007 and Master’s degree from Bengal Engineering and Science University, India, in 2009. She is currently a Ph.D. student in Mechanical Engineering at the Indian Institute of Technology (IIT), Kanpur, India under the supervision of Prof. Ashish Dutta. Her current research focuses towards the rough terrain path planning, kinematics and dynamic analysis of autonomous planetary rover, redundancy resolution of rover and manipulator, learning.

306

R. Raja et al. / Robotics and Autonomous Systems 72 (2015) 295–306

A. Dutta obtained his Ph.D. in Systems Engineering from Akita University, Japan. From 1994 to 2000 he was with the Bhabha Atomic Research Center (India) where he worked on telemanipulator design and control for nuclear applications. Since 2002 he has been with the Department of Mechanical Engineering at the Indian Institute of Technology Kanpur, India. Briefly, he was also an Assistant Professor at Nagoya University, Japan from 2006 to 2007 in the Department of Mechanical Science and Engineering. His research interests are in the areas of humanoid robotics, micro sensors and actuators, intelligent control systems and rehabilitation engineering.

K.S. Venkatesh obtained his Ph.D. in Signal Processing from the Indian Institute of Technology (IIT) Kanpur, India. From 1995 to 1999 he was an Assistance Professor in IIT Guwahati. Since 1999 he has been with the Department of Electrical Engineering at the Indian Institute of Technology Kanpur, India. His research interests are in the areas of Image Analysis and Processing (Conventional and Morphological); Multidimensional and Multivariate (Colour) Signal Representation; Transforms; Generalized Signal and System.