INTERNATIONAL JOURNAL OF COMPUTERS COMMUNICATIONS & CONTROL ISSN 1841-9836, 13(6), 1007-1031, December 2018. Simulation of Rapidly-Exploring Random Trees in Membrane Computing with P-Lingua and Automatic Programming I. Pérez-Hurtado, M.J. Pérez-Jiménez, G. Zhang, D. Orellana-Martín Ignacio Pérez-Hurtado*, Mario J. Pérez-Jiménez, David Orellana-Martín Research Group on Natural Computing Department of Computer Science and Artificial Intelligence University of Seville, Seville, Spain {perezh,marper,dorellana}@us.es *Corresponding author: perezh@us.es Gexiang Zhang School of Electrical Engineering Southwest Jiaotong University, Chengdu, Shichuan, China zhgxdylan@126.com Abstract: Methods based on Rapidly-exploring Random Trees (RRTs) have been widely used in robotics to solve motion planning problems. On the other hand, in the membrane computing framework, models based on Enzymatic Numerical P systems (ENPS) have been applied to robot controllers, but today there is a lack of planning algorithms based on membrane computing for robotics. With this motivation, we provide a variant of ENPS called Random Enzymatic Numerical P systems with Proteins and Shared Memory (RENPSM) addressed to implement RRT algorithms and we illustrate it by simulating the bidirectional RRT algorithm. This paper is an extension of [21]a. The software presented in [21] was an ad-hoc simulator, i.e, a tool for simulating computations of one and only one model that has been hard-coded. The main contribution of this paper with respect to [21] is the introduction of a novel solution for membrane computing simulators based on automatic programming. First, we have extended the P-Lingua syntax –a language to define membrane computing models– to write RENPSM models. Second, we have implemented a new parser based on Flex and Bison to read RENPSM models and produce source code in C language for multicore processors with OpenMP. Finally, additional experiments are presented. Keywords: Membrane Computing, RENPSM, robotics, RRT, P-Lingua. aReprinted (partial) and extended, with permission based on License Number 501431225 ©[2018] IEEE 7th International Conference on Computers Communications and Control (ICCCC) 1 Introduction Robots are machines oriented to objectives equipped with actuators, sensors and computation units acting under physical constraints. Regardless of their morphology, they should accomplish tasks by acting in the real world. This is one of the main reasons by which robot motion planning is an eminent research area in robotics [8, 11, 21]. In general terms, the problem of motion planning can be defined in the configuration space of a robot as follows: Given a start configuration state, a goal configuration state, a geometric description of the robot, and a geometric description of the environment, find a path that moves the robot gradually from start to goal. A configuration state is a specification of the positions of all robot points relative to a fixed coordinate system. This is usually expressed as a vector of positions and orientations, for ex- ample, a rigid-body robot in a 2D world can be expressed as a vector (x,y,θ) representing the Copyright ©2018 CC BY-NC 1008 I. Pérez-Hurtado, M.J. Pérez-Jiménez, G. Zhang, D. Orellana-Martín center (x,y) of the robot in a fixed coordinate system and its yaw angle θ, i.e, the heading angle of the robot. Since the shape of the robot is described, all of its points are then known. Several constraints can be added to this problem, the most common is to reach the goal while never touching any obstacle in the environment. Others can also be added, for example, a social robot could restrict configuration states in order to guarantee the human comfort. The configuration space of a robot can also be constrained by the type of movements the robot can perform. In this sense, nonholonomic robots are those that cannot instantly modify its direction without employing rotation in-place. On the other hand, holonomic robots can do it (assuming zero mass). For example, a holonomic robot in a 2D world can move along the x axis and the y axis, as well as modify its yaw angle if needed. But a nonholonomic robot can only move forward/backward and/or modify its yaw angle. This is the typical case of dual-wheeled mobile robots and cars. Classical path planning algorithms have been widely adapted and applied to the problem of motion planning with constraints in robots, for example, in [26], an application of the Dijkstra algorithm for robot path-planning was presented. In such solutions, the general problem is usually divided into two smaller problems: the global path planning problem, as described above; and the local path planning, where the robot tries to connect two consecutive states in real-time considering features not included in the global plan as, for example, dynamic obstacles. The accumulated error during the local planning conducts to periodically recompute the global plan. For this reason, the computational complexity of global planners is a critical point regarding to real-time constraints. Many efforts have been made to provide good global planners. For example: in [25], a search algorithm, called D∗, was presented for path planning in real-time environments. In [15], a variant of the classical search algorithm A∗ is applied to grids with blocked and unblocked cells. In [12], a tool for global path planning, called Rapidly-Exploring Random Trees (RRT), was presented. The class of RRT algorithms for global path planning is based on the randomized exploration of the configuration space before moving the robot by building a tree in memory where nodes represent states that can be reached by the state of the corresponding parent in a fixed amount of time, furthermore each edge contains a velocity reference to reach the state in the child node from the state in the parent node. It is currently one popular method in robot motion planning due to its good properties. The computed RRT can be used together with search algorithms or, as presented in [13], the RRT generation algorithm can be used by itself as a path planning algorithm, where two RRTs are built simultaneously, one beginning from the initial configuration and another one beginning from the ending configuration (bidirectional RRT). In order to follow the path in safe manner, a local planner module should be executed considering dynamic obstacles. Finally, each motor of the robot must be able to reach and maintain velocity references for fixed periods of time. This is the function of a type of software called controller on-board of the robot. Thus, robot control [1] is the branch of robotics dedicated to the study and practice of controlling robots. Robot controllers are usually based on common silicon microprocessors, but in the recent years, some classes of membrane systems [16] have been in use for modelling them [18] [19] [20] [29]. Membrane systems are models of computation based on the structure and functions of the living cells. In a membrane system, there are objects being evolved inside compartments according to rules applied in a non-deterministic, maximally parallel way. They have been used as a new technique to attack the P versus NP problem [22], and several applications have been also stud- ied: stochastic P systems for modelling biological phenomena [24], probabilistic P systems for modelling real ecosystems [2], spiking neural P systems incorporating fuzzy reasoning, for fault diagnosis and learning [27], and others. With respect to robot control, numerical P systems (NPS) were used for modelling and sim- Simulation of Rapidly-Exploring Random Trees in Membrane Computing with P-Lingua and Automatic Programming 1009 ulating robot controllers [20], although the initial application of NPS was related to economical processes [17]. A variant called enzymatic numerical P systems (ENPS) [18] was introduced and applied to the distributed control of a swarm of mobile robots. Indeed, reactive and proportional- integral-derivative (PID) dual-wheeled robot controllers have been successfully designed and sim- ulated by means of ENPS, as well as software simulation tools [29]. This variant has been also used [19] to address robot localization problem [8], where the robot must know its position in the environment by using sensors. In [21], following [23], a new variant of ENPS called random enzymatic numerical P sys- tems with proteins and shared memory (RENPSM, for short) was introduced. New syntactical ingredients were included to fit the requirements of the RRT algorithm: • Random numbers: The algorithm uses a randomized method to explore the physical space, therefore random numbers must be generated. • Shared memory: The algorithm is parallelized using processes sharing common variables, and a distinguished membrane, called shared memory, is included. At any instant, each membrane can read from or write to it. • Proteins: In order to synchronize the sequential execution of the algorithm, proteins are used. This paper is an extension of [21]. The software presented in [21] was an ad-hoc simulator, i.e, a tool to simulate computations of one and only one model that has been hard-coded. Ad-hoc simulators can be optimized for specific hardware architectures, but they are less debug-friendly than generic simulators, since changes in the model imply changes in the source code of the simulator. On the other hand, P-Lingua [3, 7, 33] is a language to define membrane computing models, there are several simulators based on P-Lingua, most of them are implemented in the pLinguaCore library [33] in Java language. In this paper, we provide a novel approximation taking the advantages of ad-hoc and generic simulators by using automatic programming. We have implemented a tool for parsing P-Lingua files defining RENPSM models and generating source code in C and OpenMP for ad-hoc simulators. Thus, we have a flexible way to debug since we are using a language to define the models instead of hard-coding them in the source code. Moreover, the generated source code is able to run on multicore processors by using OpenMP. Furthermore, additional virtual experiments are presented in this paper. This paper is structured as follows. In the next section, some notions about robot path planning are introduced. In Section 3, the rapidly-exploring random trees (RRTs) are described with some details. Section 4 is devoted to introduce random enzymatic numerical P systems with proteins and shared memory. In Section 5, a RENPSM model for the bidirectional RRT algorithm is described. In Section 6, the original software presented in [21] based on C++ and ROS [30] is explained, including some experimental results. In Section 7, the new software presented in this paper is introduced, including an extension of the P-Lingua syntax for RENPSM, as well as additional experiments. Finally, conclusions and future work are drawn. 2 Robot path planning In general terms, robot path planning can be solved by applying a solution based on three modules: • Global planner: It receives the desired ending configuration of the robot, its safety radius and current localization, as well as the precomputed position of the static obstacles in 1010 I. Pérez-Hurtado, M.J. Pérez-Jiménez, G. Zhang, D. Orellana-Martín the environment and current information of sensors and odometry. The current dynamic obstacles detected by the sensors are added to the static ones in order to generate a more descriptive information of the environment. The odometry is used to obtain the current velocity of the robot when kinodynamic constraints are considered. Then, the global plan- ner computes a plan from the starting configuration xinit to the desired final configuration xend of the robot. The plan is represented as a sequence of local goals {gi|1 ≤ i ≤ n}, where g1 = xinit and gn = xend. Each goal can be reachable from the previous goal con- sidering the constraints of the problem, i.e, avoiding static obstacles, nonholonomic and kinodynamic constraints, etc. RRT algorithms and other similar algorithms can be used for this task. • Local planner: It receives the sequence of local goals generated by the global planner, as well as the current information of sensors, localization and odometry, then it sends velocity references to the controller in order to command the robot along the path. Several algo- rithms such as the dynamic window approach [5], pure pursuit [4], and potential fields [10] algorithms, among others and variants, can be used. • Controller: It receives velocity references from the local planner and manages the power of the motors to fit each reference and maintain it constant or accelerate or reduce it until the next one. In Figure 1, it is represented the general robot path planning cycle. First the robot computes a global plan from its current pose to the desired ending pose; if the plan can be generated, i.e, the robot could reach the destination considering all the constraints, then the local planner receives a sequence of intermediate goals and sends velocity references to the PID controller in order to follow the path in a safe manner until reaching the destination; if some error occurs, for example, a dynamic obstacle is too close to the next local goal or the robot is too far from the next local goal (considering a predefined threshold), then the global plan is recomputed from the current robot position. Notice that if there is a dynamic obstacle too close to the ending configuration, then the global plan cannot be found. 3 Rapidly-exploring Random Trees An RRT [12] is a randomized tree structure for rapidly exploring in memory a state space X from an initial state xinit. It can be successfully used for nonholonomic and kinodynamic global path planning in robotics [13]. Nodes in an RRT represent possible reachable states, for mobile robots in a 2D world which is given by (x,y,θ) where (x,y) are the Cartesian coordinates of the robot position and θ is the heading angle. However, the heading angle can be omitted in order to reduce the size of the tree. It is assumed that a fixed obstacle region Xobs ⊆ X must be avoided, so the nodes of the RRT are states in Xfree, the complement of Xobs in X. Edges in an RRT represent transitions between reachable states, each of which is labelled with the velocity reference u that the robot should execute for a fixed period of time ∆t in order to change the corresponding states. For a mobile robot in a 2D world, the velocity reference can be represented by the pair of linear and angular velocities (v,ω) to be sent to the controller. On the other hand, if θ has been omitted, the edges in the RRT are labelled with instant linear velocities. Thus, a holonomic robot can reach a state x1 from another state x0 connected by an edge labelled with u by applying x1 = x0 + u ·∆t. In the case of nonholonomic robots, the local planner should select the best sequence of motions in order to approximate x1, for example, if Simulation of Rapidly-Exploring Random Trees in Membrane Computing with P-Lingua and Automatic Programming 1011 Figure 1: Robot path planning cycle the robot can rotate in-place, a naive solution is to perform a rotation in-place before developing the motion in a straight line. Algorithm 1 GENERATE_RRT Require: xinit,K,ρ, ∆t,X,Xobs,dmin 1: Vτ ←{xinit}; Eτ ←∅; 2: for k = 1 to K do 3: xrand ← RANDOM_STATE(X); 4: EXTEND(τ,xrand,ρ, ∆t,Xobs,dmin); 5: end for 6: return τ = (Vτ,Eτ ) Algorithm 1 is an iterative method to generate an RRT using the function EXTEND defined in Algorithm 2, where: • xinit is the initial state. • K is the number of iterations to build the RRT. • ρ is a prefixed distance metric. • ∆t is a fixed amount of time for transitions. 1012 I. Pérez-Hurtado, M.J. Pérez-Jiménez, G. Zhang, D. Orellana-Martín Algorithm 2 EXTEND Require: τ,x,ρ, ∆t,Xobs,dmin 1: xnear ← NEAREST_NEIGHBOR(x,τ); 2: if DISTANCE(x,xnear) ≥ dmin then 3: u ← SELECT_INPUT(x,xnear); 4: if ¬ COLLISION(xnear,u, ∆t,Xobs) then 5: xnew ← NEW_STATE(xnear,u, ∆t); 6: Vτ ← Vτ ∪{xnew} 7: Eτ ← Eτ ∪{(xnear,xnew)} 8: if DISTANCE(x, xnew) < dmin then 9: return Reached; 10: else 11: return Advanced; 12: end if 13: else 14: return Trapped; 15: end if 16: else 17: return Trapped; 18: end if • X is the state space. • Xobs is the obstacle state space. • dmin is the minimum distance threshold according to ρ in order to include a new node in the RRT. • τ = (Vτ,Eτ ) is the RRT generated. • RANDOM_STATE(X) is a function to get a random state from X • NEAREST_NEIGHBOR(x,τ) is a function to get the closest node to x in τ according to ρ. • DISTANCE(x,xnear) is a function to get the distance of x to xnear according to ρ. • SELECT_INPUT(x,xnear) is a function to get the velocity input that should be com- manded to the robot in order to achieve state x from xnear. • COLLISION(xnear,u, ∆t,Xobs) is a function returning true if a collision could be produced moving the robot from state xnear by applying the input u for ∆t time considering the obstacles in Xobs. • NEW_STATE(xnear,u, ∆t) is a function to get a new state xnew by applying the input u to the robot for ∆t time starting at state xnear. The function EXTEND tries to add a new node to the RRT τ considering a reference x. If the function fails, then it returns Trapped; if the new node is closer than dmin to x, then it returns Reached; and if the new node is far from x considering dmin, then the function returns Advanced. Figure 2 describes a RRT generated after 5000 iterations by using Algorithm 1 with the Euclidean distance and omitting the heading angle. Simulation of Rapidly-Exploring Random Trees in Membrane Computing with P-Lingua and Automatic Programming 1013 Figure 2: RRT generated after 5000 iterations In [13], a bidirectional RRT algorithm was introduced for path planning. The main idea of this algorithm is to create two RRTs: τa starting at xinit and τb starting at xend. If τa and τb are connected in a prefixed number K of iterations, then a path is returned; otherwise the function returns failure. Algorithm 3 GENERATE_PATH Require: xinit,xend,K,ρ, ∆t,X,Xobs,dmin 1: Vτa ←{xinit}; Eτa ←∅; 2: Vτb ←{xend}; Eτb ←∅; 3: for k = 1 to K do 4: xrand ← RANDOM_STATE(X); 5: if EXTEND(τa,xrand,ρ, ∆t,Xobs,dmin) 6= Trapped then 6: if EXTEND(τb,xnew,ρ, ∆t,Xobs,dmin) = Reached then return PATH(τa, τb); 7: end if 8: end if 9: SWAP(τa, τb); 10: end for 11: return Failure Algorithm 3 is the bidirectional RRT algorithm presented in [13], where: • xinit is the initial state. • xend is the ending state. • τa = (Vτa,Eτa ) is an RRT starting at xinit. • τb = (Vτb,Eτb ) is an RRT starting at xend. • PATH(τa, τb) is a function to compute a path from the initial node of τa to the initial node of τb. Both RRTs must be connected. • SWAP(τa, τb) is a procedure to interchange the values of τa and τb. 1014 I. Pérez-Hurtado, M.J. Pérez-Jiménez, G. Zhang, D. Orellana-Martín The rest of variables have the same meaning than the variables used in Algorithms 1 and 2. In this paper we propose the Algorithm 4 as a parallel version of the bidirectional RRT algorithm, where τa and τb are built at the same time. Algorithm 4 GENERATE_PATH_PARALLEL Require: (xinit,xend,K,ρ, ∆t,X,Xobs,dmin 1: Vτa ←{xinit}; Eτa ←∅; 2: Vτb ←{xend}; Eτb ←∅; 3: for k = 1 to K do 4: xrand,a ← RANDOM_STATE(X); 5: xrand,b ← RANDOM_STATE(X); 6: loop 7: resulta = EXTEND(τa,xrand,a,ρ, ∆t,Xobs,dmin); 8: resultb = EXTEND(τb,xrand,b,ρ, ∆t,Xobs,dmin); 9: end loop 10: if resulta 6= Trapped then 11: if EXTEND(τb,xnew,ρ, ∆t,Xobs,dmin) = Reached then return PATH(τa, τb); 12: end if 13: end if 14: if resultb 6= Trapped then 15: if EXTEND(τa,xnew,ρ, ∆t,Xobs,dmin) = Reached then return PATH(τa, τb); 16: end if; 17: end if; 18: end for; 19: return Failure 4 Random enzymatic numerical P systems with proteins and shared memory In this section a variant of enzymatic numerical P systems incorporating new features is presented, in order to simulate RRT algorithms. A random enzymatic numerical P systems with proteins and shared memory (RENPSM, for short) of degree (p,q), p,q ≥ 1 is a tuple (H,µ,P,Emem,Emem(0), {Ph(0),V arh,V arh(0),Prh) | h ∈ H},R,ha,hb), where: 1. H = {1, . . . ,p · q}∪{v,mem}, mem /∈ {1, . . . ,p · q}, v /∈ {mem, 1, . . . ,p · q}, is the set of labels of the system; 2. µ is a dynamic membrane structure (rooted tree) initially consisting of one skin membrane with label v including two inner membranes labelled respectively with ha ∈ {1, . . . ,p · q} and hb ∈ {1, . . . ,p · q}, ha 6= hb, in such manner that along the computation only child membranes of ha and hb will be created with labels in {1, . . . ,p · q}. In Figure 3, it is represented the initial membrane structure; 3. mem is the label of a distinguished component (the shared memory of the system); 4. P is a finite set of objects, called catalyzer proteins, and Ph(0) is the protein initially associated with region labelled by h; Simulation of Rapidly-Exploring Random Trees in Membrane Computing with P-Lingua and Automatic Programming 1015 5. Emem is a finite set of variables, called enzymes, disjoint with V armem, and Emem(0) is the initial values of the enzymes; 6. V arh,h ∈ H, is a finite set of variables xj,h associated with region labelled by h (a mem- brane or the shared memory), its values are natural numbers and the value of xj,i at time t ∈ N is denoted by xj,i(t); 7. V arh(0) is a vector that represents the initial values for variables in V arh; 8. Prh,h ∈ H, is a finite set of programs associated with region labelled by h, having the fol- lowing syntactical format F(x1,h, . . . ,xkF ,h) e(F);α(F) −−−−−−−−−−−−−→ c1|v1, . . . ,cnF |vnF , where: – F(x1,h, . . . ,xkF ,h) is a computable function (the production function), being x1,h, . . . ,xkF ,h ∈ V arh; – c1|v1, . . . ,cnF |vnF is the repartition protocol associated with the program, being c1, . . . ,cnF natural numbers specifying the proportion of the current production distributed to variables v1, . . . ,vnF ∈ V arh∪V arpar(h)∪V arch(h), where par(h) is the parent of h and ch(h) is the set of child of h in µ; – e(F) ∈ Eh is an enzyme and α(F) ∈ P is a protein, both of them associated with program F , if no enzyme or protein is used in a program then it will be omitted; 9. R is a finite set of rules of the following form: – Protein evolution rules: [ α → α′ ]h, where h ∈ H,α ∈ P and α′ ∈ P . – Writing-only communication rules between the shared memory and the membranes (h, Xh /Yh,mem , mem) W α where Xh ∈ V arh,Yh,mem ∈ V armem,α ∈ P in such manner that there is, at most, one rule for each membrane h ∈ {1, . . . ,p · q}. Variables Yh,mem,Yh′,mem should be different for two membranes h,h′. – Reading-only communication rules between the shared memory and the membranes: (h, Xh /Ymem , mem) R α where Xh ∈ V arh,Ymem ∈ V armem,α ∈ P . Variable Ymem is the same for each h ∈{1, . . . ,p ·q}. – Membrane creation rules:[ [ X1,h , X2,h, , . . . , Xn,h ] h ] h′ ; α where h,h′ ∈{1, . . .p ·q ·r} are different, α ∈ P and X1,h , . . . , Xn,h ⊆ V arh. The term region h (h ∈ H) is used to refer to membrane h in the case h ∈{1, . . . ,p ·q}∪{v}, as well as to refer to the shared memory in the case h = mem. Next, we describe the semantics of RENPSHs. A configuration of a RENPSH at any instant t is described by the current membrane structure µ, together with proteins and all values of the variables and enzymes associated with all regions. The initial configuration is (µ,Emem(0),{Ph(0),V arh(0)|h ∈ H}), where µ = [[ ]ha [ ]hb ]v. We will call µa (resp. µb) to the membrane structure rooted in membrane ha (resp. hb). 1016 I. Pérez-Hurtado, M.J. Pérez-Jiménez, G. Zhang, D. Orellana-Martín Figure 3: The initial membrane structure with a representation of the shared memory. A program F(x1,h, . . . ,xkF ,h) eF ;pF−→ c1|v1, . . . ,cnF |vnF associated with a region is applicable to a configuration Ct at moment t, if the value of e(F) at that instant is greater than min{x1,h(t), . . . ,xkF ,h(t)} and protein α(F) is inside the region h of Ct. When applying such a program, variables associated withCt are processed as follows: first, the value F(x1,h(t), . . . ,xkF ,h(t)) is computed as well as the value q(t) = F(x1,h(t), . . . ,xkF ,h(t)) c1 + · · · + cnF This value represents the unary portion at instant t to be distributed among variables v1, . . . ,vnF according to the repartition expression. Thus, q(t) · cs is the contribution added to the current value of vs (1 ≤ s ≤ nF ), at step t + 1. So, vs(t + 1) = vs(t) + q(t) · cs and vs(t) become zero, i.e, it is assumed that variable vs is "consumed" when the production function is used and other variables retain their values. Each program in each membrane can only be used once in every computation step, and all the programs are executed in parallel. A protein evolution rule [ α → α′ ]h is applicable to a configuration Ct at moment t if protein α is in membrane h of Ct. When applying such a rule the protein α in h evolves to protein α′ in h. These rules are applied in a maximal manner. A writing-only communication rule between the shared memory and the membranes, (h, Xh /Yh,mem , mem) W α , is applicable to a configuration Ct at moment t if protein α is in membrane h of Ct. When applying such a rule the value Xh(t) is assigned to the variable Yh,mem(t + 1) of the shared memory, that is Yh,mem(t + 1) ← Xh(t) . These rules are applied in a maximal manner. A reading-only communication rule between the shared memory and the membranes, (h, Xh /Ymem , mem) R α is applicable to a configuration Ct at moment t if protein α is in membrane h of Ct. When applying such a rule the value Ymem(t) is assigned to the variable Xh(t + 1) of membrane h, that is Xh(t + 1) ← Ymem(t). These rules are applied in a maximal manner. A membrane creation rule [ [X1,h , . . . , Xn,h ]h ]h′ ; α is applicable to a configuration Ct at moment t if protein α is in membrane h′ of Ct. When applying such a rule, a new membrane labelled by h is created in such manner that h′ is the parent of h and the set of its variables is V arh = {X1,h , . . . , Xn,h}. Given a random enzymatic numerical P system with proteins and shared memory Π, we say that configuration Ct at time t yields configuration Ct+1 in one transition step if we can pass from Ct to Ct+1 by applying in parallel each program in each membrane only once, and by applying the rules in a maximal parallel way following the previous remarks. A computation of Π is a (finite Simulation of Rapidly-Exploring Random Trees in Membrane Computing with P-Lingua and Automatic Programming 1017 or infinite) sequence of configurations such that: (a) the first term is the initial configuration of the system; (b) for each n ≥ 2, the n-th configuration of the sequence is obtained from the previous configuration in one transition step; and (c) if the sequence is finite (called halting computation) then the last term is a halting configuration (a configuration where no rule of the system is applicable to it). All the computations start from an initial configuration and proceed as stated above; only halting computations give a result, which is encoded by the objects present in the output region iout associated with the halting configuration. If C = {Ct}t Table 1: Benchmarking results Min. cost 11.77 m Max. cost 17.96 m Average cost 13.42 m Standard deviation 0.795 m Experiments 1435 1026 I. Pérez-Hurtado, M.J. Pérez-Jiménez, G. Zhang, D. Orellana-Martín Figure 6: A second simulation in environment 2 • The initial membrane structure is defined as a two level cell-like membrane structure: @mu = [[]′h1[]′h2...[]′hN]′v where h1, h2,...,hN and v are numeric labels in N. The label 0 is used the shared memory. P-Lingua variables can optionally be used instead of literals. • Each RENPSM variable includes at least one index. The last index of each variable is the label of the compartment containing the variable. For instance, the variable X1,mem is written X{1,0}. For the sake of simplicity, indexes will be omitted in the rest of this section. • Proteins are written as common objects in P-Lingua. • Production rules are written in the next manner: X < −func(param1,param2, ...,paramN),protein?enzyme where X is a RENPSM variable; func is a production function with parameters param1,param2, ...,paramN, protein is an optional protein related to the rule and enzyme is an optional enzyme. There are a fixed set of production functions that can be used. In this paper, we have implemented the functions for the model in Section 5. More functions could be implemented in C language. The rule will be executed if the protein is present and the enzyme has a value greater than zero. • Reading-only and writing-only communication rules are respectively written as follows: X < −Y,protein?enzyme Y < −X,protein?enzyme where X is a variable in the membrane structure, Y is a variable in the shared memory, protein is an optional protein related to the rule and enzyme is an optional enzyme. The rule will be executed if the protein is present and the enzyme has a value greater than zero. • Membrane creation rules are written as follows: Simulation of Rapidly-Exploring Random Trees in Membrane Computing with P-Lingua and Automatic Programming 1027 [[]′h1]′h2,protein?enzyme where h1, h2 are labels that can be given by numeric literals, P-Lingua variables or even RENPSM variables; protein is an optional protein related to the rule and enzyme is an optional enzyme. The rule will be executed if the protein is present and the enzyme has a value greater than zero. • Protein evolution rules are written in the next manner: [p1 < −p2]′h where p1 and p2 are proteins and h is the label of a compartment, given by a numeric literal or a P-Lingua variable. • We have created an special iterator x in H to iterate all the membrane labels in the tree structure rooted at H (with a depth-first order). • Other ingredients of P-Lingua, such as modules, indexes, iterators and comments can be used as usual in this extension. The whole P-Lingua file defining the model presented in 5 can be downloaded from https://github.com/RGNC/renpsm_openmp/blob/master/birrt_renpsm_test1.pli. 7.2 A parser to generate ad-hoc RENPSM simulators A parser based on Flex and Bison [35,36] has been implemented and can be downloaded from https://github.com/RGNC/renpsm_openmp. The website includes instructions for compiling and running the experiments in this paper. The parser reads a P-Lingua file and generates a command-line ad-hoc simulator tool that accepts a PGM file defining the obstacles and generates another PGM file printing the generated RRT over the obstacles image. The source code of the simulator tool is generated in C with OpenMP, the command-line syntax for the generated simulator is: ./simulator [-t threads] [-s steps] [-d] [-r seed] [-m obstacles.pgm] [-o output.pgm] Where: • -t threads is the number of threads to be used. Default is 4. If 1 thread is set, the simulator will be sequential. • -s steps is the maximum number of computational steps to simulate. The simulator stops if the variable Haltmem is set to 1 or the number of steps is reached. Default is 1048576 steps. • If -d is set, debug information will be prompted. • -r seed defines the pseudo-random number generator seed. If no seed is configured, an arbitrary seed based on the current clock time will be used. • -m obstacles.pgm is the PGM file defining the obstacle grid for the collision function. • -o output.pgm is the PGM file to print the output RRT over the obstacle image. 1028 I. Pérez-Hurtado, M.J. Pérez-Jiménez, G. Zhang, D. Orellana-Martín (a) (b) (c) (d) Figure 7: Example outputs for environment 1: (a) Example output 1; (b) Example output 2; (c) Example output 3; (d) Example output 4 (a) (b) (c) (d) Figure 8: Example outputs for environment 2: (a) Example output 1; (b) Example output 2; (c) Example output 3; (d) Example output 4 7.3 Experimental results We have used the same two environments presented in Section 6. The environment 1 is defined with the files: birrt_renpsm_test2.pli; office.pgm. The environment 2 is defined with the files: birrt_renpsm_test1.pli; map.pgm. Each environment uses a PGM file in gray scale for obstacle definition, where each pixel represents a region of 5 cm2 in the real world. Each environment also uses a P-Lingua file with identical P system definition but different initial parameters p, q, x0, y0, x1, y1. The problem is to find a RRT representation to navigate from (x0,y0) to (x1,y1) in the environment of p pixels length and q pixels height given by the corresponding PGM file. In Figures 7 and 8 there are four example outputs for each environment using the correspond- ing generated ad-hoc simulator with 8 threads and arbitrary pseudo-random number generator seeds based on the CPU clock time. 8 Conclusions This paper deals with an algorithm belonging to a family widely used to solve the problem of motion planning in robots, e.g., the RRT algorithms. Such class of algorithms are based on the randomized exploration of the configuration space. This paper is an extension of [21]. In such a work, a variant of Enzymatic Numerical P systems, called random enzymatic numerical Simulation of Rapidly-Exploring Random Trees in Membrane Computing with P-Lingua and Automatic Programming 1029 P systems with proteins and shared memory (RENPSM, for short) was introduced. Besides, a simplified version of the standard bidirectional RRT algorithm was described by a RENPSM system capturing the semantics of the new variant, where maximal parallelism is used. The main contribution of this paper with respect to [21] is to provide a novel approximation for software simulation by using automatic programming. We have implemented a tool for parsing P-Lingua files defining RENPSM models and generating source code in C and OpenMP for ad-hoc simulators. Thus, we have a flexible way to debug since we are using a language to define the models instead of hard-coding them in the source code. Moreover, the generated source code is able to run on multicore processors by using OpenMP. Three main challenges are planned as future work. First, to provide a formal verification of such RENPSM systems, in the sense that they in fact simulate the RRT generation algorithm. The second challenge is to move to the RRT* algorithm [9], a variant of the initial algorithm that is able to approximate optimal motion planning with enough iterations. Finally, to provide real-life robot path planning experiments, by using a nonholonomic robot with kinodynamic and environment constraints. We also propose to apply the simulation techniques introduced in this paper to other types of P systems walking towards a more generic software tool based on P-Lingua and automatic programming for generation of optimized ad-hoc simulators. Acknowledgements This work was supported by National Natural Science Foundation of China (61672437 and 61702428) and by Sichuan Science and Technology Program (2018GZ0086, 2018GZ0185). Authors from the University of Seville also acknowledge the support of the research project TIN2017-89842-P, co-financed by Ministerio de Economía, Industria y Competitividad (MINECO) of Spain, through the Agencia Estatal de Investigación (AEI), and by Fondo Europeo de Desar- rollo Regional (FEDER) of the European Union. Bibliography [1] Astrom, K.J.; Hagglund, T. (1995). PID Controllers: Theory, Design, and Tuning, 1995 [2] Colomer, M.A.; Margalida, A.; D. Sanuy,D.; Pérez-Jiménez, M.J. (2011). A bio-inspired computing model as a new tool for modeling ecosystems: The avian scavengers as a case study. Ecological Modelling, 222 (1), 33-47, 2011. [3] Díaz-Pernil, D.; Pérez-Hurtado, I.; Pérez-Jiménez, M.J. ; Riscos-Núñez, A. (2009). A P- Lingua Programming Environment for Membrane Computing. Lecture Notes in Computer Science, 5391, 187–203, 2009. [4] Coulter, C. (1992). Implementation of the Pure Pursuit Path Tracking Algorithm, Tech. Re- port, CMU-RI-TR-92-01, Robotics Institute, Carnegie Mellon University, 1992. [5] Fox, D.; Burgard, W.; Thrun, S. (1997). The dynamic window approach to collision avoidance, Robotics and Automation Magazine, 4 (1), 23-33, 1997. [6] Gao, Y.; Wu, X.; Liu, Y.; Li, J.M.; Liu J.H.(2017). A Rapid Recognition of Impassable Terrain for Mobile Robots with Low Cost Range Finder Based on Hypotheses Testing Theory, International Journal of Computers Communications & Control, 12(6), 813-823, 2017. 1030 I. Pérez-Hurtado, M.J. Pérez-Jiménez, G. Zhang, D. Orellana-Martín [7] García-Quismondo, M.; Gutiérrez-Escudero, R.; Martínez-del-Amor, M.A.; Orejuela-Pinedo, E.; Pérez-Hurtado, I. (2009). P-Lingua 2.0: A software framework for cell-like P systems. International Journal of Computers Communications & Control, 4(3), 234-243, 2009. [8] Huang, S.; Dissanayake, G. (2016). Robot Localization: An Introduction, Wiley Encyclopedia of Electrical and Electronics Engineering, 2016 [9] Karaman, S.; Frazzoli, E. (2010). Incremental Sampling-based Algorithms for Optimal Mo- tion Planning, Robotics Science and Systems VI, 1-9, 2010 [10] Khatib, O. (1986). Real-time obstacle avoidance for manipulators and mobile robots, Int J Robot Res, 5(1), 90-98, 1986. [11] Latombe, J.C. (1991). Robot Motion Planning, Kluwer Academic Publishers, Boston, MA, 1991. [12] LaValle, S.M. (1998). Rapidly-Exploring Random Trees: A New Tool for Path Planning, Computer Science Dept., Iowa State University, October 1998. [13] LaValle, S.M. ; Kuffner, J.J. (1999). Randomized kinodynamic planning, Proceedings IEEE International Conference on Robotics and Automation, 473-479, 1999. [14] Martínez-del-Amor, M.A.; Pérez-Hurtado, I.; Pérez-Jiménez, M.J.; Riscos-Núñez, A. (2010). A P-Lingua based simulator for Tissue P Systems, Journal of Logic and Algebraic Program- ming, 79 (6), 374-382, 2010. [15] Nash, A.; K. Daniel, Koenig,S.; Felner, A. (2010). Theta: Any-Angle Path Planning on Grids, Journal of Artificial Intelligence Research, 39, 533-579, 2010. [16] Păun, G. (2010). Computing with membranes, Journal of Computer and System Sciences, 61 (1), 108-143, 2000. [17] Păun, G., Păun R. (2006). Membrane Computing and Economics: Numerical P Systems, Fundamenta Informaticae, 73(1,2), 213–227, 2006. [18] Pavel, A.; Arsene, O.; Buiu, C. (2010). Enzymatic Numerical P Systems - A New Class of Membrane Computing Systems, Proceedings of IEEE fifth international conferenced on bio-inspired computing: Theories and applications (BIC-TA), 1331-1336, 2010. [19] Pavel, A.; Vasile, C.; Dumitrache, I. (2012). Robot localization implemented with enzymatic numerical P systems, Proceedings of the international conference on biomimetic and biohybrid systems, 204-215, 2012. [20] Pavel, A.; Buiu, C. (2012). Using enzymatic numerical P systems for modeling mobile robot controllers, Natural Computing, 11(3), 387-393, 2012. [21] Pérez, I.; Pérez-Jiménez, M.J.; Zhang, G.; Orellana-Martín D. (2018). Robot path planning using rapidly-exporing random trees: A membrane computing approach, 2018 IEEE 7th In- ternational Conference on Computers Communications and Control, Proc. of (ICCCC2018), Oradea, Romania, May 08-12, 37-46, 2018. [22] Pérez-Jiménez, M.J.(2014); The P versus NP problem from Membrane Computing view, European Review, 22 (1), 18–33, 2014. Simulation of Rapidly-Exploring Random Trees in Membrane Computing with P-Lingua and Automatic Programming 1031 [23] Pérez-Hurtado, I. Pérez-Jiménez, M.J. (2017). Generation of rapidly-exploring random tree by using a new class of membrane systems. Pre-proceedings of Asian Conference on Membrane Computing (ACMC2017), Chengdu, China, September 21-25, 534-546, 2017. [24] Romero-Campero, F.J.; Pérez-Jiménez, M.J. (2008). A Model of the Quorum Sensing Sys- tem in Vibrio fischeri Using P Systems. Artificial Life, 14 (1), 95-109, 2008. [25] Stentz, A. (1995). The Focussed D* Algorithm for Real-time Replanning, Proceedings of the 14th International Joint Conference on Artificial Intelligence, 2, 1652-1659, 1995. [26] Wang, H.; Yu, Y.; Q. Yuan, Q. (2011). Application of Dijkstra algorithm in robot path- planning, Proceedings of the 2nd International Conference on Mechanic Automation and Control Engineering, 1067-1069, 2011. [27] Wang, T.; Zhang, G.; Zhao, J.; He, Z.; Wang, J.; Pérez-Jiménez, M.J. (2015). Fault di- agnosis of electric power systems based on fuzzy reasoning spiking neural P systems. IEEE Transactions on Power Systems, 30(3), 1182 - 1194, 2015. [28] Widyotriatmo, A.; Joelianto, E.; Prasdianto, A.; Bahtiar, H.; Nazaruddin, Y.Y. (2017). Implementation of Leader-Follower Formation Control of a Team of Nonholonomic Mobile Robots, International Journal of Computers Communications & Control, 12(6), 871-885, 2017. [29] Zhang, G.; Perez-Jimenez, M.J.; Gheorghe, M. (2017). Real-life Applications with Mem- brane Computing, Series: Emergence, Complexity and Computation, Volume 25. Springer International Publishing, 2017. [30] http://www.ros.org [31] http://www.mobilerobots.com/Software/MobileSim.aspx [32] http://wiki.ros.org/rviz [33] http://www.p-lingua.org/wiki/index.php/Main_Page [34] https://developer.nvidia.com/cuda-zone [35] https://github.com/westes/flexl [36] https://www.gnu.org/software/bison/ [37] https://www.openmp.org/