source: trunk/extremum_seeking/esc_nn/src/node_2d.cpp @ 11

Last change on this file since 11 was 5, checked in by wcaarls, 12 years ago

Imported extremum_seeking at revision 987

File size: 1.9 KB
Line 
1/*
2 * node.cpp
3 *
4 *  Created on: Jul 31, 2012
5 *      Author: Berk Calli
6 *      Organization: Delft Biorobotics Lab., Delft University of Technology
7 *              Contact info: b.calli@tudelft.nl, web: www.dbl.tudelft.nl
8 *
9 *      Node for two dimensional neural network extremum seeking control
10 */
11
12#include <esc_nn/nn_esc_2d.h>
13#include "esc_ros/esc_ros.h"
14
15int main(int argc, char **argv) {
16
17        ros::init(argc, argv, "nn_esc_2d");
18        ros::NodeHandle n("~");
19
20        double A, B, M, ddelta1, ddelta2, ddelta3, delta, period;
21        if (!n.getParam("A", A)){
22                ROS_WARN("[nn_esc_2d]: Failed to get the parameter A from the parameter server. Using the default value.");
23                A = 0;
24        }
25        if (!n.getParam("B", B)){
26                ROS_WARN("[nn_esc_2d]: Failed to get the parameter B from the parameter server. Using the default value.");
27                B = 0;
28        }
29        if (!n.getParam("M", M)){
30                ROS_WARN("[nn_esc_2d]: Failed to get the parameter M from the parameter server. Using the default value.");
31                M = 0;
32        }
33        if (!n.getParam("ddelta1", ddelta1)){
34                ROS_WARN("[nn_esc_2d]: Failed to get the parameter ddelta1 from the parameter server. Using the default value.");
35                ddelta1 = 0;
36        }
37        if (!n.getParam("ddelta2", ddelta2)){
38                ROS_WARN("[nn_esc_2d]: Failed to get the parameter ddelta2 from the parameter server. Using the default value.");
39                ddelta2 = 0;
40        }
41        if (!n.getParam("ddelta3", ddelta3)){
42                ROS_WARN("[nn_esc_2d]: Failed to get the parameter ddelta3 from the parameter server. Using the default value.");
43                ddelta3 = 0;
44        }
45        if (!n.getParam("delta", delta)){
46                ROS_WARN("[nn_esc_2d]: Failed to get the parameter delta from the parameter server. Using the default value.");
47                delta = 0;
48        }
49        if (!n.getParam("period", period)){
50                ROS_WARN("[nn_esc_2d]: Failed to get the parameter period from the parameter server. Using the default value.");
51                period = 0;
52        }
53
54        ESCROS esc_ros(&n);
55        NNESC2D* nn_esc_2d = new NNESC2D(A,M,B,ddelta1,ddelta2,ddelta3,delta,period);
56        esc_ros.init(nn_esc_2d);
57        esc_ros.spin();
58
59        return 0;
60}
61
62
Note: See TracBrowser for help on using the repository browser.