source: trunk/extremum_seeking/esc_nn/src/node_1d.cpp @ 47

Last change on this file since 47 was 18, checked in by wcaarls, 12 years ago

Updated extremum_seeking to revision 1177

File size: 2.1 KB
Line 
1/*
2 * node.cpp
3 *
4 *  Created on: July 24, 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 neural network extremum seeking control
10 */
11
12#include <esc_nn/nn_esc_1d.h>
13#include "esc_ros/esc_ros.h"
14
15int main(int argc, char **argv) {
16
17        ros::init(argc, argv, "nn_esc_1d");
18        ros::NodeHandle n("~");
19
20        double A, B, M, ddelta, delta, period,stoping_min_val;
21        int stopping_cycle_number;
22        if (!n.getParam("A", A)){
23                ROS_WARN("[nn_esc_1D]: Failed to get the parameter A from the parameter server. Using the default value.");
24                A = 0;
25        }
26        if (!n.getParam("B", B)){
27                ROS_WARN("[nn_esc_1D]: Failed to get the parameter B from the parameter server. Using the default value.");
28                B = 0;
29        }
30        if (!n.getParam("M", M)){
31                ROS_WARN("[nn_esc_1D]: Failed to get the parameter M from the parameter server. Using the default value.");
32                M = 0;
33        }
34        if (!n.getParam("ddelta", ddelta)){
35                ROS_WARN("[nn_esc_1D]: Failed to get the parameter ddelta from the parameter server. Using the default value.");
36                ddelta = 0;
37        }
38        if (!n.getParam("delta", delta)){
39                ROS_WARN("[nn_esc_1D]: Failed to get the parameter delta from the parameter server. Using the default value.");
40                delta = 0;
41        }
42
43        if (!n.getParam("period", period)){
44                ROS_WARN("[nn_esc_1D]: Failed to get the parameter period from the parameter server. Using the default value.");
45                period = 0;
46        }
47
48        if (!n.getParam("stopping_condition/cycle_number", stopping_cycle_number)){
49                ROS_WARN("[nn_esc_1D]: Failed to get the parameter stopping_condition/cycle_number from the parameter server. Using the default value.");
50                stopping_cycle_number = 0;
51        }
52
53        if (!n.getParam("stopping_condition/min_val_change_per_cycle", stoping_min_val)){
54                ROS_WARN("[nn_esc_1D]: Failed to get the parameter stopping_condition/min_val_change_per_cycle from the parameter server. Using the default value.");
55                stoping_min_val = 0;
56        }
57
58        ESCROS esc_ros(&n);
59        NNESC1D* nn_esc_1d = new NNESC1D(A,M,B,ddelta,delta,period,stopping_cycle_number,stoping_min_val);
60        esc_ros.init(nn_esc_1d);
61        esc_ros.spin();
62
63        return 0;
64}
Note: See TracBrowser for help on using the repository browser.