Technical Specifications of the Robotic System [19]
Abstract
This chapter describes a novel nature-inspired and intelligent control system for mobile robot navigation using a fuzzy-molecular inference (FMI) system as the control strategy and a single vision-based sensor device, that is, image acquisition system, as feedback. In particular, FMI system is proposed as a hybrid fuzzy inference system with an artificial hydrocarbon network structure as defuzzifier that deals with uncertainty in motion feedback, improving robot navigation in dynamic environments. Additionally, the robotics system uses processed information from an image acquisition device using a real-time Hermite optical flow approach. This organic and nature-inspired control strategy was compared with a conventional controller and validated in an educational robot platform, providing excellent results when navigating in dynamic environments with a single-constrained perception device.
Keywords
- Artificial organic networks
- artificial hydrocarbon networks
- fuzzy-molecular inference system
- robotics
- optical flow
1. Introduction
Navigation of mobile robots is still a challenging problem due to the uncertain and dynamics of environments [1]. Typically, navigation consists of different tasks [1] such as: perception, exploration, mapping, localization, path planning, and path execution. In this work, navigation is limited to a strategy or methodology that guides a mobile robot to accomplish a task through an environment with obstacles—static or dynamic—without collisions, using sensors. Also, this work considers a robotic system with a unique vision-based sensor for perception.
Artificial intelligence (AI) has been widely used for navigation of mobile robots. Different AI methods have been proposed, such as: fuzzy logic [2], artificial neural networks [3], hybrid neuro-fuzzy controllers [4–6], evolutionary and meta-heuristics algorithms [7], and nature-inspired computing (e.g., particle swarm optimization and ant colony optimization) [8, 9]. Artificial intelligence has been used in different levels of cognition such as: reasoning, decision-making, and learning.
Furthermore, some applications using AI-based controllers and features based on optical flow to compute the control law are present in the literature. For instance, Williams et al. [10] propose a support vector machines (SVM)—kernel to carry out vehicle tracking using optical flow features. Meta-cognitive neuro-fuzzy inference systems (McFIS) for accurate detection of human actions from video sequences have been proposed by Subramanian et al. [11]. In fact, they employ optical flow-based features, and the functional relationship between these optical flow-based features and action classes is approximated using the McFIS classifier. Boroujeni et al. [12] propose a method for obstacle detection using optical flow and
In that way, this work proposes a novel nature-inspired and intelligent controller for navigation of mobile robots constrained to a single vision-based sensor, using a recent hybrid fuzzy inference system and artificial hydrocarbon networks (AHN) approach so-called fuzzy-molecular inference (FMI) system. This fuzzy-molecular inference system inherits characteristics from fuzzy inference systems (FIS) such as storage of knowledge from experts, dealing with uncertainty, and linguistic interpretation [15]; but also from artificial organic networks (AON), a learning method inspired on chemical organic compounds that allow packaging information in molecular units, organizing of information, and dealing with aggressive uncertainty and noise [16]. In advance, fuzzy-molecular inference systems can deal with uncertainty and under aggressive conditions of noise, with relative easiness of implementation [15]. Examples of FMI-based controllers can be found in literature [15, 17]. In addition, this proposed controller uses a real-time Hermite optical flow (RT-HOF) approach for detecting direction of moving objects in the visual range of the mobile robot. In fact, RT-HOF is a method that determines the displacement of each pixel at some time in an image sequence representing the motion of objects in the scene or the relative motion of the sensor, with the usage of the Hermite transform (HT) [18] as a biological image model in real-time. This RT-HOF approach has been proved to be easy to implement and faster than conventional optical flow methods [19], giving advantages to be used in online navigation.
The rest of the chapter is organized as follows: Section 2 briefly describes the fundamentals of the proposal: artificial hydrocarbon networks algorithm as part of artificial organic networks method, the fuzzy-molecular inference system, and the real-time Hermite optical flow method. Section 3 formalizes the proposed nature-inspired and intelligent control for mobile robots and its design. Later on, Section 4 describes the implementation of the proposed artificial organic controller in a mobile robot system. Section 5 presents experimental results of the proposed controller, and Section 6 concludes the work.
2. Nature-inspired and intelligent computing
This section describes the fundamentals of the proposed controller for robot navigation. First, artificial hydrocarbon networks learning algorithm is introduced. Then, the fuzzy-molecular inference system is described, and lastly, the real-time Hermite optical flow approach is presented.
2.1. Artificial hydrocarbon networks
Artificial hydrocarbon networks (AHN) is a nature-inspired learning algorithm based on the artificial organic networks framework. In fact, artificial organic networks (AON) technique is a meta-heuristic method and framework inspired on chemical organic structures and the energy involved in the interaction among them. Inspiration of AON method considers packaging information in independent structures named molecules which they can relate among them using chemical energy-based heuristics [16]. Therefore, AON method provides modularity, inheritance, organization, and structural stability in the output response [16].
Thus, artificial hydrocarbon network method is a supervised learning technique that inherits from AON framework, restricted in the shape and type of molecules occupied [16]. From the latter, AHN is inspired on chemical hydrocarbon compounds that constraint the method only using two atomic units, that is, hydrogen and carbon atoms, that can be related together with at most one and four degrees of freedom, respectively, as described below.
The basic unit with information of AHN is the so-called
Then, these molecules can form other types of structures so-called compounds, which include nonlinear relationships among all molecules [16]. In this work, forming compounds are restricted to be linear and saturated compounds like Eq. (2), where
In terms of the behavior of the compound, it is expressed as a nonlinear function
Lastly, an artificial hydrocarbon network is a mixture

Figure 1.
AHN Algorithm to Create an Artificial Hydrocarbon Network.
Chemical heuristic rules for searching and building an optimum artificial hydrocarbon network with specific carbon and hydrogen values are computed using the so-called AHN-algorithm depicted in Figure 1 (for a detailed description, see for example [21]). Finally, examples of applications using this technique can be found in literature [20, 22–24].
2.2. Fuzzy-molecular inference system
Fuzzy-molecular inference (FMI) systems are ensembles of artificial hydrocarbon networks and fuzzy inference systems [15] that consist of three steps: fuzzification, fuzzy inference engine, and molecular defuzzification. The overall process maps crisp inputs to a fuzzy space, and resulting values are returned to as crisp outputs using a molecular approach based on artificial hydrocarbon networks. In addition, a knowledge base stores information about a specific problem [15].
The basis fuzzy-molecular rule is shown in Eq. (5), where
First at the fuzzification step, the fuzzy-molecular inference system receives an input signal
The second step considers the fuzzy inference engine as a mechanism that computes the consequent value
Lastly, the molecular defuzzification step computes the crisp output value
The proper knowledge of the specific problem domain can be enclosed into a knowledge base, summarizing all fuzzy rules of Eq. (6), assigning any
2.3. Real-time Hermite optical flow
Optical flow (OF) is defined as a two dimensional distribution of “apparent velocities” of the objects in the scene that in most cases are associated with intensity variations of the objects into an image sequence [26]. It is represented by a vector field that represents the displacement of pixels. For example, Figure 2 shows the vector field obtained from frames 43 and 44 of the camera motion sequence [27].

Figure 2.
Optical Flow Representation in a Sequence of Images [
Classical differential optical flow methods assume that the intensity value of the objects remain constant in two consecutive time instants of an image sequence
If small displacements are assumed, a Taylor expansion is considered; and the
If only the constant intensity constraint is used, it is not possible to determine the two components of displacement
Horn and Schunck [28] proposed the
The Hermite transform is an image model based in a polynomial decomposition from a perceptual standpoint. This image model emulates the local processing and the response of receptive fields, for example, the Gaussian derivative model of the human vision system [31, 32]. In fact, it is computed by convolution of the image
The filter functions

Figure 3.
Hermite Filters
The steered Hermite transform (SHT) can be defined by rotating the cartesian Hermite coefficients
The steered Hermite coefficients

Figure 4.
An Ensemble of the Steered Hermite Coefficients of the
The steered Hermite transform can be used to increase the accuracy of the optical flow by using a biological image model and by incorporating the steered Hermite coefficients as constraint independent to intensity changes. In [19], a modified version of Horn and Schunck approach was proposed. This includes an expansion of the
Applying a Taylor expansion of Eq. (17) and reducing terms using the relation
Where

Figure 5.
Pseudocode for the Real-Time Hermite Optical Flow [
Using variational calculus, the corresponding Euler–Lagrange equations computed are like in Eqs. (19) and (20) where
3. Nature-inspired and intelligent controller for robot navigation
As stated above, this work proposes a nature-inspired and intelligent controller for navigation of mobile robots constrained to a single vision-based sensor, like Figure 6. In fact, this artificial organic controller consists of a fuzzy-molecular inference system as the control strategy (i.e., using a hybrid fuzzy inference system with artificial hydrocarbon networks), and a motion feedback from a single vision-based sensor that processes image sequences using the real-time Hermite optical flow approach. Following, main components of the artificial organic controller are described.

Figure 6.
Block Diagram of the Proposed Artificial Organic Control.
3.1. Control law based on a Fuzzy-molecular inference system
Consider a mobile robot with a single vision-based sensor, for example, a video camera, which it can move around a flat environment. If the environment consists of static and dynamic obstacles, the aim of the motion controller is to avoid obstacles as well as to move the robot in a proper way.
In that sense, the robot perceives the environment through the camera, obtaining relative displacements of the objects in front of the robot (see Section 3.2) in two axes: horizontal (
3.1.1. Fuzzification step
The design of this step considers selecting the set of inputs to the controller. As described above, two inputs are used: relative horizontal displacement
3.1.2. Fuzzy inference engine step
This step requires the definition of fuzzy rules with respect to the goal of the controller. Notice that the consequent values
3.1.3. Molecular defuzzification step
The last step of the proposed controller considers the computation of the control signal
As restricted in previous section, the set of

Figure 7.
Example of the Structural Formula Representation of an Artificial Hydrocarbon Compound.
3.2. Motion feedback using the RT-HOF approach
A vision-based sensor is proposed to use in mobile robots in order to retrieve motion feedback. In particular, a video camera located in front of the robot can be used. For instance, two adjacent images are obtained. Then, the real-time Hermite optical flow algorithm is used to compute relative displacements of objects between the two images. This procedure outputs a map of displacements. Since the relative displacements in the map are two dimensional vectors, decomposition in horizontal (
If one object at the time is in front of the video camera, then
4. Implementation on navigation mobile robots
This section introduces the case study employed for implementing and validating the proposed artificial organic controller based on the FMI system and the RT-HOF approach for motion feedback. First, a description of the robotics system is presented. Then, the design of the particular artificial organic controller is shown. Lastly, it describes the process of calibration of the motion feedback system.
4.1. Description of the robotics system
The robotics system used in this case study is based on a previous work reported in [19]. The mobile robot was implemented with the LEGO Mindstorms EV3 as both the mechanical and the electrical platform because it is easy and practical to use. The robot was built as tank configuration using two direct current (DC) motors and two rubber bands as actuators, and the robot was planned to be in a differential steering configuration. Also, a webcam was mounted on the robot to be used as the single vision-based sensor. For experimental purposes, the intelligent brick of the LEGO Mindstorms EV3 set was used as the interface between the mobile robot and a computer with MATLAB. The latter was employed to compute the control of the whole system. Both the webcam and the intelligent brick communicated with the computer via USB. Figure 8 shows a diagram of the robotic system [19]. The technical specifications of the robotic system are summarized in Table 1.

Figure 8.
Schematic of the Robotic System Used in the Case Study Based on [
|
|
---|---|
Webcam sensor | 1.3 M pixels, 1280 × 1024 max resolution |
DC motor actuators | 9V-input, 0.55A-nominal, 2.03 W mechanical power, 4.95 W electrical power, 160 rpm max nominal |
USB communication | 9600 baud rate |
Windows-based workstation | Intel Xeon Six-Core Processor 2.6 GHz, 32 GB RAM |
Table 1.
4.2. Design of the artificial organic controller
The fuzzy-molecular inference system-based controller was developed using the methodology described in Section 3. Two inputs were selected as follows: relative mean horizontal displacement

Figure 9.
Input Membership Functions of

Figure 10.
Input Membership Functions of
In addition, Table 2 shows the set of fuzzy rules to this artificial organic controller, and Figure 11 shows the artificial hydrocarbon compound developed for this case study. Notice that there are three
|
|
|
|
---|---|---|---|
Table 2.
Set of Fuzzy Rules Used in the Artificial Organic Controller

Figure 11.
Structural Formula of the Proposed Artificial Hydrocarbon Compound.
4.3. Calibration of the motion feedback
Previous work [19] proved that the real-time Hermite optical flow algorithm (Figure 5) can be used in soft and hard real-time frameworks, arising the opportunity to employ this technique in mobile robots.
In fact, the motion feedback system implemented in this work acquires images at 100ms of frame rate. Then, a pair of two adjacent images are analysed using the real-time Hermite optical flow algorithm of Figure 5. A map of the displacements is then obtained showing where objects in images are moving. In particular, an automated segmentation is done in order to get only the displacements that reach an empirical threshold, assuming that dynamic obstacles perform displacements greater than this threshold. For this case study, a threshold value of
5. Experimental results
In order to validate the performance of the proposed controller, three tests were conducted about the actions taken from the mobile robot when dealing with dynamic obstacles. In addition, a comparison between the proposed controller and a rule-based controller previously developed in [19] was run. In the following section, these experimental results are summarized.
5.1. Tests on avoiding dynamic obstacles
This experiment consisted on steering the robot when dynamic objects are across the vision range of it. In particular, the robot avoids the obstacle in the opposite direction of its movement. In that sense, the proposed artificial organic controller is able to compute the relative displacement of the obstacle with respect to the robot, and then, the nature-inspired control strategy could calculate the power supply offering to the two motors, independently.
In advance, three tests were conducted. The first test considered the dynamic object (i.e., another robot) to move from left-to-right perpendicular to the direction of the robot, expecting that the robot steers to the left. The second test consisted in the same dynamic object, but moving from right-to-left perpendicular to the direction of the robot, expecting that the latter moves to the right. Finally, the third test considered a dynamic obstacle moving in a perpendicular direction with respect to the direction of the robot. Tables 3 to 5 summarize the mean relative horizontal
|
|
|
|
|
---|---|---|---|---|
0.00 | 0.00 | 15.1 | 15.1 | |
1.73 | 0.88 | -15.1 | 15.1 | |
1.22 | 2.09 | -15.1 | 15.1 | |
1.01 | -0.03 | 0.0 | 8.7 | |
0.00 | 0.00 | 15.1 | 15.1 |
Table 3.
(Left-to-Right Test) Inputs and Outputs Values of the Artificial Organic Controller
|
|
|
|
|
---|---|---|---|---|
−2.34 | -0.64 | 15.1 | 0.0 | |
−0.86 | -0.53 | 8.0 | −0.2 | |
−0.26 | -1.18 | 4.2 | 4.5 | |
0.11 | 0.61 | 9.5 | 9.2 | |
−1.01 | -0.36 | 15.1 | 0.0 | |
-0.56 | -0.26 | 1.3 | 0.2 |
Table 4.
(Right-to-Left Test) Inputs and Outputs Values of the Artificial Organic Controller
|
|
|
|
|
---|---|---|---|---|
−1.39 | 0.28 | 15.1 | −15.1 | Right (fast) |
−0.24 | 0.23 | 4.7 | 5.2 | Straight |
0.28 | 0.16 | 2.8 | 2.3 | Straight |
−0.48 | 0.22 | 1.2 | 0.3 | Stop |
−1.29 | 0.90 | 15.1 | −15.1 | Right (fast) |
Table 5.
(Diagonal Test) Inputs and Outputs Values of the Artificial Organic Controller

Figure 12.
Test 1 (Left-to-Right): Trajectory Response of the Artificial Organic Controller.

Figure 13.
Test 2 (Right-to-Left): Trajectory Response Of The Artificial Organic Controller.

Figure 14.
Test 3 (Diagonal): Trajectory Response of the Artificial Organic Controller.
Observing at Figures 12 and 13, the correction of the direction is done fast in the robot while looking the dynamic obstacle in front. Reactiveness in the third test (Figure 14) is quite lower than in the first two tests. Currently, the robot can avoid obstacles in all situations. As an example, Figure 15 shows the visual range of the robot and the relative displacements obtained from the RT-HOF algorithm.

Figure 15.
Example of the Visual Range of the Robot and the Relative Displacements Obtained from the RT-HOT Algorithm.
5.2. Comparison of mobile robot navigation controllers
An inspection comparison was also done in order to highlight advantages and limitations on the performance of the proposed artificial organic controller. In fact, the controller in the previous work [19] reported a rule-based controller. Figures 16 to 18 show the response of the avoidance obstacles in the same configuration of tests: Dynamic object moves from left-to-right, from right-to-left and in diagonal, respectively.

Figure 16.
Test 1 (Left-to-Right): Trajectory Response of the Rule-Based Controller [

Figure 17.
Test 2 (Right-to-Left): Trajectory Response of the Rule-Based Controller [

Figure 18.
Test 3 (Diagonal): Trajectory Response Of The Rule-Based Controller [
First, the new artificial organic controller has better performance in terms of time reaction. Using the rule-based controller, the robot reacts in large time with respect to the distance of the dynamic object. It also considers a slow action that can be seen in the curvature of the depicted trajectory, and the robot does not return to the main direction (once the direction is corrected, the robot does not go back to the previous direction). The latter might be a disadvantage in the overall time of navigation, and the orientation of the robot could be lost.
On the other hand using the proposed artificial organic controller, the robot reacts in short time with respect to the distance of the dynamic object. In addition, once the steering is performed, the power supply to the wheels is recovered to the initial power. Moreover, the action is done fast (in contrast with the other controller) and the direction of the robot comes back close to the initial orientation. As an advantage, this controller might be used to surround dynamic obstacles that can minimize the overall time of the performance.
It is remarkable to say that the rule-based controller is a reactive approach in contrast to the deliberative approach performed with the artificial organic controller. From the perspective of agents systems, deliberative approaches can deal with uncertainty, imprecise, and noise in a suitable way [37]. In addition, the artificial organic controller can be more scalable, reliable, and easy to understand. In advance, using the hybrid fuzzy-molecular inference system gives an easy way to tune and interpret the performance of the controller, in comparison with the rule-based controller. Lastly, learnability is allowed in the proposed controller.
6. Conclusions
This chapter presents a novel artificial organic controller for mobile robot navigation, based on a hybrid fuzzy-molecular inference system as the nature-inspired control strategy and a single vision-based motion feedback using the real-time Hermite optical flow approach.
In fact, this artificial organic controller proposed the fuzzy-molecular inference system because it inherits characteristics from fuzzy inference systems like storage of knowledge from experts, dealing with uncertainty, and linguistic interpretation; but also from artificial hydrocarbon networks method that allows packaging information in molecular units, organizing of information, and dealing with aggressive uncertainty and noise. In addition, this proposed controller uses a real-time Hermite optical flow approach.
Experimental results showed that the proposed artificial organic controller can avoid dynamic obstacles. In addition, the comparison with a rule-based controller highlights that the proposed controller is easy to implement and to understand. Also, it is scalable and reliable in terms of uncertainty, imprecise, and noise.
For future work, this research is looking for implementing a learning mechanism in the artificial organic controller in order to automate the adaptation to the environment, and membership functions could be tuned automatically. To this end, complex environments should be tested to improve the real-time Hermite optical flow algorithm.
References
- 1.
Barrera, A., editor. Mobile Robots Navigation. ISBN: 978-953-307-076-6, InTech; 2010. pp. 680. Available from: http://www.intechopen.com/books/mobile-robots-navigation - 2.
Llorca, D., Milanes, V., Alonso, P., Gavilan, M., Daza, I., Perez, J., Sotelo, M., Autonomous Pedestrian Collision Avoidance Using a Fuzzy Steering Controller. IEEE Transactions on Intelligent Transportation Systems. 2011; 12 (2):390–401. - 3.
Tsankova, D., Neural Networks Based Navigation and Control of a Mobile Robot in a Partially Known Environment. In: Barrera, A., editor. Mobile Robots Navigation. ISBN: 978-953-307-076-6, InTech; 2010. p. 197–222. Available from: http://www.intechopen.com/books/mobile-robots-navigation/neural-networks-based-navigation-and-control-of-a-mobile-robot-in-a-partially-known-environment - 4.
Kayacan, E., Ramon, H., Kaynak, O., Saeys, W., Towards Agrobots: Trajectory Control of an Autonomous Tractor Using Type-2 Fuzzy Logic Controllers. IEEE/ASME Transactions on Mechatronics. 2014; 20 (1):287–298. - 5.
Ponce, P., Molina, A., Mendoza, R., Ruiz, M., Monnrad, D., Fernandez, L., Intelligent Wheelchair and Virtual Training by LabVIEW. In: Sidorov, G., Hernandez, A., Reyes, C., editors. Advances in Artificial Intelligence. Switzerland: Springer; 2010. p. 422–435. doi:10.1007/978-3-642-16761-4_37 - 6.
Ponce, P., Molina, A., Mendoza, R. Wheelchair and Virtual Environment Trainer by Intelligent Control. In: Iqbal, S., Boumella, N., Figueroa, J., editors. Fuzzy Controllers—Recent Advances in Theory and Applications. InTech; 2012. - 7.
Juang, C., Lai, M., Zeng, W., Evolutionary Fuzzy Control and Navigation for Two Wheeled Robots Cooperatively Carrying an Object in Unknown Environments. IEEE Transactions on Cybernetics. 2014; 45 (9):1731–1743. - 8.
Juang, C., Chang, Y., Evolutionary-Group-Based Particle-Swarm-Optimizer Fuzzy Controller with Application to Mobile-Robot Navigation in Unknown Environments. IEEE Transactions on Fuzzy Systems. 2011; 19 (2):379–392. - 9.
Ponce, H., editor. Nature-Inspired Computing for Control Systems. 1st edn. Switzerland: Springer; 2016. pp. 289. doi:10.1007/978-3-319-26230-7 - 10.
Williams, O., Blake, A., Cipolla, R., A Sparse Probabilistic Learning Algorithm for Real-Time Tracking. In: 9th IEEE International Conference on Computer Vision; 2003. - 11.
Subramanian, K., Suresh, S., Human Action Recognition Using Meta-Cognitive Neuro-Fuzzy Inference System. In: 2012 International Joint Conference on Neural Networks; 2012. p. 1–8. - 12.
Boroujeni, N., Etemad, S., Whitehead, A., Fast Obstacle Detection Using Targeted Optical Flow. In: 19th IEEE International Conference on Image Processing; 2012. p. 65–68. - 13.
Narayanan, V., Crane, C., Active Relearning for Robust On-Road Vehicle Detection and Tracking Control. In: 13th International Conference on Automation and Systems; 2013. p. 124–129. - 14.
Crnko, P., Capson, D., Biomimetic Measurement of Optical Flow and Centroid for Visual-Servo Control of Hover Flight. In: 2012 IEEE International Instrumentation and Measurement Technology Conference; 2012. p. 348–353. - 15.
Ponce, H., Ponce, P., Molina, A., Artificial Hydrocarbon Networks Fuzzy Inference System. Mathematical Problems in Engineering. 2013; 2013 (2013):531031. doi:10.1155/2013/531031 - 16.
Ponce, H., Ponce, P., Molina, A., Artificial Organic Networks: Artificial Intelligence Based on Carbon Networks. Switzerland: Springer; 2014. pp. 228. - 17.
Molina, A., Ponce, H., Tello, G., Ramirez, M., Artificial Hydrocarbon Networks Fuzzy Inference Systems for CNC Machines Position Controller. The International Journal of Advanced Manufacturing Technology. 2014; 72 (9):1465–1479. - 18.
Moya-Albor, E., Escalante-Ramirez, B., Vallejo, E., Optical Flow Estimation in Cardiac CT Images Using the Steered Hermite Transform. Signal Processing. 2013; 28 (3):267–291. - 19.
Moya-Albor, E., Brieva, J., Ponce, H., Mobile Robot With Movement Detection Controlled by a Real-Time Optical Flow Hermite Transform. In: Ponce, H., editor. Nature-Inspired Computing for Control Systems. Switzerland: Springer; 2016. p. 231–263. - 20.
Ponce, H., Ponce, P., Molina, A., Adaptive Noise Filtering Based on Artificial Hydrocarbon Networks: An Application to Audio Signals. Expert Systems with Applications. 2013; 41 (14):6512–6523. - 21.
Ponce, H., Ponce, P., Molina, A., The Development of an Artificial Organic Networks Toolkit for LabVIEW. The Journal of Computational Chemistry. 2015; 36 (7):478–492. - 22.
Ponce, H., Ponce, P., Molina, A., A Novel Robust Liquid Level Controller for Coupled-Tanks Systems Using Artificial Hydrocarbon Networks. Expert Systems with Applications. 2015; 42 (22):8858–8867. - 23.
Ponce, H., Miralles-Pechuan, L., Martinez-Villaseñor, M., Artificial Hydrocarbon Networks for Online Sales Prediction. In: Pichardo, O., Herrera, O., Arroyo, G., editors. Advances in Artificial Intelligence and Its Applications; Springer; 2015. p. 498–508. doi:10.1007/978-3-319-27101-9_38 - 24.
Ponce, H., Martinez-Villaseñor, M., Miralles-Pechuan, L., Comparative Analysis of Artificial Hydrocarbon Networks and Data-Driven Approaches for Human Activity Recognition. In: Garcia-Chamizo, J., Fortino, G., Ochoa, S., editors. Ubiquitous Computing and Ambient Intelligence: Sensing, Processing, and Using Environmental Information; Springer; 2015. p. 150–161. doi:10.1007/978-3-319-26401-1_15 - 25.
Ponce, H., Ibarra, L., Ponce, P., Molina, A., A Novel Artificial Hydrocarbon Networks Based Space Vector Pulse Width Modulation Controller for Induction Motors. American Journal of Applied Sciences. 2014; 11 (5):789–810. doi:10.3844/ajassp.2014.789.810 - 26.
Gibson, J., The perception of the visual world. The American Journal of Psychology. 1951; 64 (1):622–625. - 27.
Liu, C., Freeman, W., Adelson, E., Weiss, Y., Human-Assisted Motion Annotation. In: IEEE Conference on Computer Vision and Pattern Recognition; IEEE; 2008. p. 1–8. - 28.
Horn, B., Schunck, B., Determining Optical Flow. Artificial Intelligence. 1981; 17 (1):185–203. - 29.
Nagel, H., Constraints for the Estimation of Displacement Vector Fields from Image Sequences. In: Proceedings of the Eighth International Joint Conference on Artificial Intelligence; 1983. p. 945–951. - 30.
Nagel, H., Enkelmann, W., An Investigation of Smoothness Constraints for the Estimation of Displacement Vector Fields from Image Sequences. IEEE Transactions on Pattern Analysis and Machine Intelligence. 1986; 8 (1):565–593. - 31.
Martens, J., The Hermite Transform: Theory. IEEE Transactions on Acoustics, Speech and Signal Processing. 1990; 38 (1):1595–1606. - 32.
Young, R., The Gaussian Derivative Theory of Spatial Vision: Analysis of Cortical Cell Receptive Field Line–Weighting Profiles. Detroit, Mich, USA: General Motors Research Laboratories; 1985. - 33.
Silvan-Cardenas, J., Escalante-Ramirez, B., The Multiscale Hermite Transform for Local Orientation Analysis. IEEE Transactions on Image Processing. 2006; 15 (1):1236–1253. - 34.
Van Dijk, A., Martens, J., Image Representation and Compression With Steered Hermite Transforms. Signal Processing. 1997; 56 (1):1–16. - 35.
Levkin, H.G.,Image Processing/Videocodecs/Programming [Internet]. 2004. Available from: http://www.hlevkin-com/TestImages/additional.htm. Accessed: 20 Jan 2013. - 36.
Moya-Albor, E., Optical Flow Estimation Using the Hermite Transform [thesis]. Mexico City, Mexico: Universidad Nacional Autonoma de Mexico; 2013. - 37.
Weiss, G., Multiagent Systems: A Modern Approach to Distributed Artificial Intelligence. London, UK: MIT Press; 2000. pp. 648.