source: trunk/extremum_seeking/esc_approx/src/node_1d.cpp @ 46

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

Imported extremum_seeking at revision 987

File size: 1.6 KB
Line 
1/*
2 * node.cpp
3 *
4 *  Created on: Jul 30, 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 approximation based extremum seeking control
10 */
11
12#include <esc_approx/approx_esc_1d.h>
13#include "esc_ros/esc_ros.h"
14
15int main(int argc, char **argv) {
16
17        ros::init(argc, argv, "approx_esc_1d");
18        ros::NodeHandle n("~");
19
20        double k_grad,init_vel;
21        int data_size, poly_degree,sampling;
22        if (!n.getParam("data_size", data_size)){
23                ROS_WARN("[approx_esc_1d]: Failed to get the parameter data_size from the parameter server. Using the default value.");
24                data_size = 0;
25        }
26        if (!n.getParam("poly_degree", poly_degree)){
27                ROS_WARN("[approx_esc_1d]: Failed to get the parameter poly_degree from the parameter server. Using the default value.");
28                poly_degree = 0;
29        }
30        if (!n.getParam("k_grad", k_grad)){
31                ROS_WARN("[approx_esc_1d]: Failed to get the parameter k_grad from the parameter server. Using the default value.");
32                k_grad = 0;
33        }
34        if (!n.getParam("init_vel", init_vel)){
35                ROS_WARN("[approx_esc_1d]: Failed to get the parameter init_vel from the parameter server. Using the default value.");
36                init_vel = 0;
37        }
38        if (!n.getParam("sampling", sampling)){
39                ROS_WARN("[approx_esc_1d]: Failed to get the parameter sampling from the parameter server. Using the default value.");
40                sampling = 0;
41        }
42
43        ESCROS esc_ros(&n);
44        ApproxESC1D* approx_esc_1d = new ApproxESC1D(data_size,poly_degree,k_grad,init_vel,sampling);
45        esc_ros.init(approx_esc_1d);
46        esc_ros.spin();
47
48        return 0;
49}
Note: See TracBrowser for help on using the repository browser.