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 | |
---|
15 | int 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,stoping_min_val; |
---|
21 | int stopping_cycle_number; |
---|
22 | if (!n.getParam("A", A)){ |
---|
23 | ROS_WARN("[nn_esc_2d]: 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_2d]: 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_2d]: Failed to get the parameter M from the parameter server. Using the default value."); |
---|
32 | M = 0; |
---|
33 | } |
---|
34 | if (!n.getParam("ddelta1", ddelta1)){ |
---|
35 | ROS_WARN("[nn_esc_2d]: Failed to get the parameter ddelta1 from the parameter server. Using the default value."); |
---|
36 | ddelta1 = 0; |
---|
37 | } |
---|
38 | if (!n.getParam("ddelta2", ddelta2)){ |
---|
39 | ROS_WARN("[nn_esc_2d]: Failed to get the parameter ddelta2 from the parameter server. Using the default value."); |
---|
40 | ddelta2 = 0; |
---|
41 | } |
---|
42 | if (!n.getParam("ddelta3", ddelta3)){ |
---|
43 | ROS_WARN("[nn_esc_2d]: Failed to get the parameter ddelta3 from the parameter server. Using the default value."); |
---|
44 | ddelta3 = 0; |
---|
45 | } |
---|
46 | if (!n.getParam("delta", delta)){ |
---|
47 | ROS_WARN("[nn_esc_2d]: Failed to get the parameter delta from the parameter server. Using the default value."); |
---|
48 | delta = 0; |
---|
49 | } |
---|
50 | if (!n.getParam("period", period)){ |
---|
51 | ROS_WARN("[nn_esc_2d]: Failed to get the parameter period from the parameter server. Using the default value."); |
---|
52 | period = 0; |
---|
53 | } |
---|
54 | |
---|
55 | if (!n.getParam("stopping_condition/cycle_number", stopping_cycle_number)){ |
---|
56 | ROS_WARN("[nn_esc_1D]: Failed to get the parameter stopping_condition/cycle_number from the parameter server. Using the default value."); |
---|
57 | stopping_cycle_number = 0; |
---|
58 | } |
---|
59 | |
---|
60 | if (!n.getParam("stopping_condition/min_val_change_per_cycle", stoping_min_val)){ |
---|
61 | 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."); |
---|
62 | stoping_min_val = 0; |
---|
63 | } |
---|
64 | |
---|
65 | ESCROS esc_ros(&n); |
---|
66 | NNESC2D* nn_esc_2d = new NNESC2D(A,M,B,ddelta1,ddelta2,ddelta3,delta,period,stopping_cycle_number,stoping_min_val); |
---|
67 | esc_ros.init(nn_esc_2d); |
---|
68 | esc_ros.spin(); |
---|
69 | |
---|
70 | return 0; |
---|
71 | } |
---|
72 | |
---|
73 | |
---|